ros gazebo机械臂仿真,手动控制与MoveIt自动控制

本文总结归纳古月居胡春旭ros机械臂教程,给出了一些error的解决方法,补充了通过python运行moveit。十分建议去看github huchunxu源代码的repository。

创建机械臂的xacro模型

首先创建一个工作空间,在工作空间中创建arm_description功能包。功能包中创建一个urdf文件夹,放入机械臂模型文件arm.xacro

<?xml version="1.0"?>
<robot name="arm" xmlns:xacro="http://ros.org/wiki/xacro"><!-- Defining the colors used in this robot --><material name="Black"><color rgba="0 0 0 1"/></material><material name="White"><color rgba="1 1 1 1"/></material><material name="Blue"><color rgba="0 0 1 1"/></material><material name="Red"><color rgba="1 0 0 1"/></material><!-- Constants --><xacro:property name="M_PI" value="3.14159"/><!-- link1 properties --><xacro:property name="link1_width" value="0.03" /><xacro:property name="link1_len" value="0.10" /><!-- link2 properties --><xacro:property name="link2_width" value="0.03" /><xacro:property name="link2_len" value="0.14" /><!-- link3 properties --><xacro:property name="link3_width" value="0.03" /><xacro:property name="link3_len" value="0.22" /><!-- link4 properties --><xacro:property name="link4_width" value="0.025" /><xacro:property name="link4_len" value="0.06" /><!-- link5 properties --><xacro:property name="link5_width" value="0.03" /><xacro:property name="link5_len" value="0.06" /><!-- link6 properties --><xacro:property name="link6_width" value="0.04" /><xacro:property name="link6_len" value="0.02" /><!-- Left gripper --><xacro:property name="left_gripper_len" value="0.08" /><xacro:property name="left_gripper_width" value="0.01" /><xacro:property name="left_gripper_height" value="0.01" /><!-- Right gripper --><xacro:property name="right_gripper_len" value="0.08" /><xacro:property name="right_gripper_width" value="0.01" /><xacro:property name="right_gripper_height" value="0.01" /><!-- Gripper frame --><xacro:property name="grasp_frame_radius" value="0.001" /><!-- Inertial matrix --><xacro:macro name="inertial_matrix" params="mass"><inertial><mass value="${mass}" /><inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="0.5" iyz="0.0" izz="1.0" /></inertial></xacro:macro><!-- ///   bottom_joint   // --><joint name="bottom_joint" type="fixed"><origin xyz="0 0 0" rpy="0 0 0" /><parent link="base_link"/><child link="bottom_link"/></joint><link name="bottom_link"><visual><origin xyz=" 0 0 -0.02"  rpy="0 0 0"/><geometry><box size="1 1 0.02" /></geometry><material name="Brown" /></visual><collision><origin xyz=" 0 0 -0.02"  rpy="0 0 0"/><geometry><box size="1 1 0.02" /></geometry></collision><xacro:inertial_matrix mass="500"/></link><!-- /   BASE LINK    // --><link name="base_link"><visual><origin xyz="0 0 0" rpy="0 0 0" /><geometry><box size="0.1 0.1 0.04" /></geometry><material name="White" /></visual><collision><origin xyz="0 0 0" rpy="0 0 0" /><geometry><box size="0.1 0.1 0.04" /></geometry></collision><xacro:inertial_matrix mass="1"/></link><joint name="joint1" type="revolute"><parent link="base_link"/><child link="link1"/><origin xyz="0 0 0.02" rpy="0 ${M_PI/2} 0" /><axis xyz="-1 0 0" /><limit effort="300" velocity="1" lower="-2.96" upper="2.96"/><dynamics damping="50" friction="1"/></joint><!-- /   LINK1  // --><link name="link1" ><visual><origin xyz="-${link1_len/2} 0 0" rpy="0 ${M_PI/2} 0" /><geometry><cylinder radius="${link1_width}" length="${link1_len}"/></geometry><material name="Blue" /></visual><collision><origin xyz="-${link1_len/2} 0 0" rpy="0 ${M_PI/2} 0" /><geometry><cylinder radius="${link1_width}" length="${link1_len}"/></geometry></collision><xacro:inertial_matrix mass="1"/></link><joint name="joint2" type="revolute"><parent link="link1"/><child link="link2"/><origin xyz="-${link1_len} 0 0.0" rpy="-${M_PI/2} 0 ${M_PI/2}" /><axis xyz="1 0 0" /><limit effort="300" velocity="1" lower="-2.35" upper="2.35" /><dynamics damping="50" friction="1"/></joint><!-- ///   LINK2  // --><link name="link2" ><visual><origin xyz="0 0 ${link2_len/2}" rpy="0 0 0" /><geometry><cylinder radius="${link2_width}" length="${link2_len}"/></geometry><material name="White" /></visual><collision><origin xyz="0 0 ${link2_len/2}" rpy="0 0 0" /><geometry><cylinder radius="${link2_width}" length="${link2_len}"/></geometry></collision><xacro:inertial_matrix mass="1"/></link><joint name="joint3" type="revolute"><parent link="link2"/><child link="link3"/><origin xyz="0 0 ${link2_len}" rpy="0 ${M_PI} 0" /><axis xyz="-1 0 0" /><limit effort="300" velocity="1" lower="-2.62" upper="2.62" /><dynamics damping="50" friction="1"/></joint><!-- /   LINK3  / --><link name="link3" ><visual><origin xyz="0 0 -${link3_len/2}" rpy="0 0 0" /><geometry><cylinder radius="${link3_width}" length="${link3_len}"/></geometry><material name="Blue" /></visual><collision><origin xyz="0 0 -${link3_len/2}" rpy="0 0 0" /><geometry><cylinder radius="${link3_width}" length="${link3_len}"/></geometry></collision><xacro:inertial_matrix mass="1"/></link><joint name="joint4" type="revolute"><parent link="link3"/><child link="link4"/><origin xyz="0.0 0.0 -${link3_len}" rpy="0 ${M_PI/2} ${M_PI}" /><axis xyz="1 0 0" /><limit effort="300" velocity="1" lower="-2.62" upper="2.62" /><dynamics damping="50" friction="1"/></joint><!-- ///   LINK4   --><link name="link4" ><visual><origin xyz="${link4_len/2} 0 0" rpy="0 ${M_PI/2} 0" /><geometry><cylinder radius="${link4_width}" length="${link4_len}"/></geometry><material name="Black" /></visual><collision><origin xyz="${link4_len/2} 0 0" rpy="0 ${M_PI/2} 0" /><geometry><cylinder radius="${link4_width}" length="${link4_len}"/></geometry></collision><xacro:inertial_matrix mass="1"/></link><joint name="joint5" type="revolute"><parent link="link4"/><child link="link5"/><origin xyz="${link4_len} 0.0 0.0" rpy="0 ${M_PI/2} 0" /><axis xyz="1 0 0" /><limit effort="300" velocity="1" lower="-2.62" upper="2.62" /><dynamics damping="50" friction="1"/></joint><!-- //   LINK5  / --><link name="link5"><visual><origin xyz="0 0 ${link4_len/2}" rpy="0 0 0" /><geometry><cylinder radius="${link5_width}" length="${link5_len}"/></geometry><material name="White" /></visual><collision><origin xyz="0 0 ${link4_len/2} " rpy="0 0 0" /><geometry><cylinder radius="${link5_width}" length="${link5_len}"/></geometry></collision><xacro:inertial_matrix mass="1"/></link><joint name="joint6" type="revolute"><parent link="link5"/><child link="link6"/><origin xyz="0 0 ${link4_len}" rpy="${1.5*M_PI} -${M_PI/2} 0" /><axis xyz="1 0 0" /><limit effort="300" velocity="1" lower="-6.28" upper="6.28" /><dynamics damping="50" friction="1"/></joint><!--    LINK6  / --><link name="link6"><visual><origin xyz="${link6_len/2} 0 0 " rpy="0 ${M_PI/2} 0" /><geometry><cylinder radius="${link6_width}" length="${link6_len}"/></geometry><material name="Blue" /></visual><collision><origin xyz="${link6_len/2} 0 0" rpy="0 ${M_PI/2} 0" /><geometry><cylinder radius="${link6_width}" length="${link6_len}"/></geometry></collision><xacro:inertial_matrix mass="1"/></link><joint name="finger_joint1" type="prismatic"><parent link="link6"/><child link="gripper_finger_link1"/><origin xyz="0.0 0 0" /><axis xyz="0 1 0" /><limit effort="100" lower="0" upper="0.06" velocity="1.0"/><dynamics damping="50" friction="1"/></joint><!-- //   gripper   // --><!-- LEFT GRIPPER AFT LINK --><link name="gripper_finger_link1"><visual><origin xyz="0.04 -0.03 0"/><geometry><box size="${left_gripper_len} ${left_gripper_width} ${left_gripper_height}" /></geometry><material name="White" /></visual><xacro:inertial_matrix mass="1"/></link><joint name="finger_joint2" type="fixed"><parent link="link6"/><child link="gripper_finger_link2"/><origin xyz="0.0 0 0" /></joint><!-- RIGHT GRIPPER AFT LINK --><link name="gripper_finger_link2"><visual><origin xyz="0.04 0.03 0"/><geometry><box size="${right_gripper_len} ${right_gripper_width} ${right_gripper_height}" /></geometry><material name="White" /></visual><xacro:inertial_matrix mass="1"/></link><!-- Grasping frame --><link name="grasping_frame"/><joint name="grasping_frame_joint" type="fixed"><parent link="link6"/><child link="grasping_frame"/><origin xyz="0.08 0 0" rpy="0 0 0"/></joint><!-- /   Gazebo   // --><gazebo reference="bottom_link"><material>Gazebo/White</material></gazebo><gazebo reference="base_link"><material>Gazebo/White</material></gazebo><gazebo reference="link1"><material>Gazebo/Blue</material></gazebo><gazebo reference="link2"><material>Gazebo/White</material></gazebo><gazebo reference="link3"><material>Gazebo/Blue</material></gazebo><gazebo reference="link4"><material>Gazebo/Black</material></gazebo><gazebo reference="link5"><material>Gazebo/White</material></gazebo><gazebo reference="link6"><material>Gazebo/Blue</material></gazebo><gazebo reference="gripper_finger_link1"><material>Gazebo/White</material></gazebo><gazebo reference="gripper_finger_link2"><material>Gazebo/White</material></gazebo><!-- Transmissions for ROS Control --><xacro:macro name="transmission_block" params="joint_name"><transmission name="tran1"><type>transmission_interface/SimpleTransmission</type><joint name="${joint_name}"><hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface></joint><actuator name="motor1"><hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface><mechanicalReduction>1</mechanicalReduction></actuator></transmission></xacro:macro><xacro:transmission_block joint_name="joint1"/><xacro:transmission_block joint_name="joint2"/><xacro:transmission_block joint_name="joint3"/><xacro:transmission_block joint_name="joint4"/><xacro:transmission_block joint_name="joint5"/><xacro:transmission_block joint_name="joint6"/><xacro:transmission_block joint_name="finger_joint1"/><!-- ros_control plugin --><gazebo><plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"><robotNamespace>/arm</robotNamespace></plugin></gazebo></robot>

Transmission for ROS Control那一部分相当于是给关节绑定上电机,通过控制电机控制关节运动。

再创建一个launch文件夹,创建view_arm.launch文件

<launch><arg name="model" /><!-- 加载机器人模型参数 --><param name="robot_description" command="$(find xacro)/xacro --inorder $(find arm_description)/urdf/arm.xacro" /><!-- 设置GUI参数,显示关节控制插件 --><!-- <param name="use_gui" value="true"/> --><!-- 运行joint_state_publisher节点,发布机器人的关节状态  --><node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" /><!-- 运行robot_state_publisher节点,发布tf  --><node name="robot_state_publisher" pkg="robot_state_publisher" type="state_publisher" /><!-- 运行rviz可视化界面 --><node name="rviz" pkg="rviz" type="rviz"/>
</launch>

运行这个launch文件,在rviz中选择fixed frame,再加载Robot Model,就可以看见机械臂了。

在Gazebo中手动控制机械臂

在工作空间中再创建一个arm_gazebo功能包,添加launch文件夹,创建arm_world.launch

<launch><!-- these are the arguments you can pass this launch file, for example paused:=true --><arg name="paused" default="false"/><arg name="use_sim_time" default="true"/><arg name="gui" default="true"/><arg name="headless" default="false"/><arg name="debug" default="false"/><!-- We resume the logic in empty_world.launch --><include file="$(find gazebo_ros)/launch/empty_world.launch"><arg name="debug" value="$(arg debug)" /><arg name="gui" value="$(arg gui)" /><arg name="paused" value="$(arg paused)"/><arg name="use_sim_time" value="$(arg use_sim_time)"/><arg name="headless" value="$(arg headless)"/></include><!-- Load the URDF into the ROS Parameter Server --><param name="robot_description" command="$(find xacro)/xacro --inorder '$(find arm_description)/urdf/arm.xacro'" /> <!-- Run a python script to the send a service call to gazebo_ros to spawn a URDF robot --><node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"args="-urdf -model arm -param robot_description"/> </launch>

功能是:创建一个环境,并且将机器人模型放进去。

下面要做的是加载控制器,首先要设定pid控制器的参数。在arm_gazebo功能包中创建config文件夹,创建arm_gazebo_control.yaml,给6个关节设定pid控制器参数。

arm:# Publish all joint states -----------------------------------joint_state_controller:type: joint_state_controller/JointStateControllerpublish_rate: 50  # Position Controllers ---------------------------------------joint1_position_controller:type: position_controllers/JointPositionControllerjoint: joint1pid: {p: 100.0, i: 0.01, d: 10.0}joint2_position_controller:type: position_controllers/JointPositionControllerjoint: joint2pid: {p: 100.0, i: 0.01, d: 10.0}joint3_position_controller:type: position_controllers/JointPositionControllerjoint: joint3pid: {p: 100.0, i: 0.01, d: 10.0}joint4_position_controller:type: position_controllers/JointPositionControllerjoint: joint4pid: {p: 100.0, i: 0.01, d: 10.0}joint5_position_controller:type: position_controllers/JointPositionControllerjoint: joint5pid: {p: 100.0, i: 0.01, d: 10.0}joint6_position_controller:type: position_controllers/JointPositionControllerjoint: joint6pid: {p: 100.0, i: 0.01, d: 10.0}

在launch文件夹中创建arm_gazebo_controller.launch,实现的作用是加载刚才创建的pid参数yaml文件,创建控制器。

<launch><!-- 将关节控制器的配置参数加载到参数服务器中 --><rosparam file="$(find arm_gazebo)/config/arm_gazebo_control.yaml" command="load"/><!-- 加载controllers --><node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"output="screen" ns="/arm" args="joint_state_controllerjoint1_position_controllerjoint2_position_controllerjoint3_position_controllerjoint4_position_controllerjoint5_position_controllerjoint6_position_controller"/><!-- 运行robot_state_publisher节点,发布tf  --><node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"respawn="false" output="screen"><remap from="/joint_states" to="/arm/joint_states" /></node></launch>

最后再创建一个arm_gazebo_control.launch文件,其作用是,运行world launch和controller launch两个launch文件。

<launch><!-- 启动Gazebo  --><include file="$(find arm_gazebo)/launch/arm_world.launch" />   <!-- 启动Gazebo controllers --><include file="$(find arm_gazebo)/launch/arm_gazebo_controller.launch" />   </launch>

运行arm_gazebo_control.launch文件,再另外打开两个terminal,分别运行

rqt
rosrun rviz rviz

通过rqt发送指令,可以在gazebo和rviz中同时看到机械臂的动作。

配置MoveIt

rosrun moveit_setup_assistant moveit_setup_assistant

依次加载模型,生成碰撞矩阵,生成规划组,如下图所示,一个arm规划组和一个gripper规划组,注意“3”那里,新版本的moveit那里不一样,空着就好。

 

 

 添加一个初始位姿,命名为home

 配置终端夹爪

最后再添加作者信息,生成配置文件就可以了。命名为arm_moveit_config,和前面创建的两个功能包arm_description, arm_gazebo并列放在一起。

用moveIt控制gazebo中的机械臂

arm_gazebo功能包中创建关节轨迹控制器,一个控制器包含两个部分:yaml配置文件和launch运行文件,yaml配置文件放在功能包的config文件夹中,里面写着控制器的参数,运行文件放在launch文件夹中,用于运行控制器。

arm_moveit_config功能包中创建一个gazebo控制器,同样是一组.yaml和.launch文件(注意这个launch文件的后缀是.launch.xml,这个文件自动存在,不需要创建,我们要改内容),launch文件加载yaml文件,分别放在config文件夹和launch文件夹。以及另外一个单独的.launch(moveit_planning_execution.launch)。

moveit功能包中的控制器和gazebo功能包中的控制器的关系是:通过ros的Action机制,moveit功能包中的控制器发布关节轨迹点指令,gazebo功能包中的控制器控制关节电机是关节到达轨迹点。

还要在arm_gazebo功能包中创建一个关节状态控制器,用于发布关节状态和tf变换。这个是为了在rviz中可视化用。

总结:一共三个控制器7个文件(3个.yaml和4个.launch)

arm_gazebo功能包中的命名为:trajectory_control.yaml    arm_trajectory_controller.launch

arm_gazebo_joint_states.yaml      arm_gazebo_states.launch

arm_moveit_config功能包中的命名为:controllers_gazebo.yaml    arm_moveit_controller_manager.launch.xml

moveit_planning_execution.launch

以上文件的内容整理在后文。最后再创建一个.launch,其作用是一次性运行上面的所有.launch。命名为arm_bringup_moveit.launch,放在arm_gazebo功能包的launch文件夹。

运行最后写的那个.launch,就可以通过rviz中的moveit插件来控制gazebo中的机械臂了。

roslaunch marm_gazebo arm_bringup_moveit.launch

 trajectory_control.yaml 内容:

arm:arm_joint_controller:type: "position_controllers/JointTrajectoryController"joints:- joint1- joint2- joint3- joint4- joint5- joint6gains:joint1:   {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}joint2:   {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}joint3:   {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}joint4:   {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}joint5:   {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}joint6:   {p: 1000.0, i: 0.0, d: 0.1, i_clamp: 0.0}gripper_controller:type: "position_controllers/JointTrajectoryController"joints:- finger_joint1gains:finger_joint1:  {p: 50.0, d: 1.0, i: 0.01, i_clamp: 1.0}

 arm_trajectory_controller.launch 内容:

<launch><rosparam file="$(find arm_gazebo)/config/trajectory_control.yaml" command="load"/><node name="arm_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"output="screen" ns="/arm" args="arm_joint_controller gripper_controller"/></launch>

arm_gazebo_joint_states.yaml 内容:

arm:# Publish all joint states -----------------------------------joint_state_controller:type: joint_state_controller/JointStateControllerpublish_rate: 50  

arm_gazebo_states.launch 内容:

<launch><!-- 将关节控制器的配置参数加载到参数服务器中 --><rosparam file="$(find arm_gazebo)/config/arm_gazebo_joint_states.yaml" command="load"/><node name="joint_controller_spawner" pkg="controller_manager" type="spawner" respawn="false"output="screen" ns="/arm" args="joint_state_controller" /><!-- 运行robot_state_publisher节点,发布tf  --><node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"respawn="false" output="screen"><remap from="/joint_states" to="/arm/joint_states" /></node></launch>

controllers_gazebo.yaml内容:

controller_manager_ns: controller_manager
controller_list:- name: arm/arm_joint_controlleraction_ns: follow_joint_trajectorytype: FollowJointTrajectorydefault: truejoints:- joint1- joint2- joint3- joint4- joint5- joint6- name: arm/gripper_controlleraction_ns: follow_joint_trajectorytype: FollowJointTrajectorydefault: truejoints:- finger_joint1- finger_joint2

arm_moveit_controller_manager.launch.xml内容:

<launch><!-- Set the param that trajectory_execution_manager needs to find the controller plugin --><arg name="moveit_controller_manager" default="moveit_simple_controller_manager/MoveItSimpleControllerManager" /><param name="moveit_controller_manager" value="$(arg moveit_controller_manager)"/><!-- load controller_list --><!-- Arbotix --><!-- <rosparam file="$(find marm_moveit_config)/config/controllers.yaml"/> --><!-- Gazebo --><rosparam file="$(find arm_moveit_config)/config/controllers_gazebo.yaml"/>
</launch>

moveit_planning_execution.launch内容:

<launch># The planning and execution components of MoveIt! configured to # publish the current configuration of the robot (simulated or real)# and the current state of the world as seen by the planner<include file="$(find arm_moveit_config)/launch/move_group.launch"><arg name="publish_monitored_planning_scene" value="true" /></include># The visualization component of MoveIt!<include file="$(find arm_moveit_config)/launch/moveit_rviz.launch"/><!-- We do not have a robot connected, so publish fake joint states --><node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher"><param name="/use_gui" value="false"/> <rosparam param="/source_list">[/arm/joint_states]</rosparam></node></launch>

arm_bringup_moveit.launch内容:

<launch><!-- Launch Gazebo  --><include file="$(find arm_gazebo)/launch/arm_world.launch" /><!-- ros_control arm launch file --><include file="$(find arm_gazebo)/launch/arm_gazebo_states.launch" />   <!-- ros_control trajectory control dof arm launch file --><include file="$(find arm_gazebo)/launch/arm_trajectory_controller.launch" /><!-- moveit launch file --><include file="$(find arm_moveit_config)/launch/moveit_planning_execution.launch" /></launch>

一些可能出现的报错:

Tried to advertise on topic but the topic is already advertised

解决办法:

arm_moveit_config功能包中,sensors_3d.yaml文件中,出现了重名topic,修改第二个topic的名称

 Unable to identify any set of controllers that can actuate the specified joints:

解决办法:修改

工作空间/src/marm_moveit_config/launch/trajectory_execution.launch.xml

删掉 pass_all_args="true"

通过python的接口运行moveit

上面是通过rviz中的插件来控制moveit,下面通过py文件来运行moveit,不需要在rviz中操作moveit插件。

还是先运行arm_bringup_moveit.launch

再运行这个py文件,group_name是在moveit_setup_assistant中配置的group,在joint_goal那里设定关节目标角度 弧度制。


import sys
import rospy
import moveit_commander
from moveit_commander import PlanningSceneInterfacemoveit_commander.roscpp_initialize(sys.argv)
rospy.init_node('move_group_python_interface_tutorial', anonymous=True)## Instantiate a `RobotCommander`_ object. Provides information such as the robot's
## kinematic model and the robot's current joint states
robot = moveit_commander.RobotCommander()## Instantiate a `PlanningSceneInterface`_ object.  This provides a remote interface
## for getting, setting, and updating the robot's internal understanding of the
## surrounding world:
scene = moveit_commander.PlanningSceneInterface()## Instantiate a `MoveGroupCommander`_ object.  This object is an interface
## to a planning group (group of joints).  In this tutorial the group is the primary
## arm joints in the Panda robot, so we set the group's name to "panda_arm".
## If you are using a different robot, change this value to the name of your robot
## arm planning group.
## This interface can be used to plan and execute motions:
group_name = "arm"
move_group = moveit_commander.MoveGroupCommander(group_name)
joint_goal = move_group.get_current_joint_values()
print(joint_goal)
joint_goal[0] = 0
joint_goal[1] = 0.9
joint_goal[2] = 0
joint_goal[3] = 0# The go command can be called with joint values, poses, or without any
# parameters if you have already set the pose or joint target for the group
move_group.go(joint_goal, wait=True)# Calling ``stop()`` ensures that there is no residual movement
move_group.stop()## END_SUB_TUTORIAL# For testing:
current_joints = move_group.get_current_joint_values()
print(current_joints)

如果是pycharm运行py文件,注意interpreter选择,我的虚拟机安装的是ubuntu18 和ros melodic,需要python2.7的interpreter,另外还要把melodic的python包放进pycharm的project structure。另外,在pycharm中添加两个环境变量。以上。

本文来自互联网用户投稿,该文观点仅代表作者本人,不代表本站立场。本站仅提供信息存储空间服务,不拥有所有权,不承担相关法律责任。如若转载,请注明出处:http://www.rhkb.cn/news/234248.html

如若内容造成侵权/违法违规/事实不符,请联系长河编程网进行投诉反馈email:809451989@qq.com,一经查实,立即删除!

相关文章

GitHub 一周热点汇总 第4期 (2024/01/01-01/06)

GitHub一周热点汇总第四期 (2023/12/24-12/30)&#xff0c;梳理每周热门的GitHub项目&#xff0c;了解热点技术趋势&#xff0c;掌握前沿科技方向&#xff0c;发掘更多商机。2024年到了&#xff0c;希望所有的朋友们都能万事顺遂。 说明一下&#xff0c;有时候本周的热点项目会…

【HarmonyOS4.0】第三篇-类web开发模式

【HarmonyOS4.0】第三篇-类web开发模式 一、鸿蒙介绍 课程核心 为什么我们需要学习鸿蒙&#xff1f; 哪些人适合直接转鸿蒙&#xff1f; 鸿蒙系统优势是什么&#xff1f; 课程内容 (1)为什么要学习鸿蒙 从行情出发&#xff1a; 美国商务部长访问中国&#xff0c;2023年…

【Java并发】深入浅出 synchronized关键词原理-下

上一篇文章&#xff0c;简要介绍了syn的基本用法和monter对象的结构&#xff0c;本篇主要深入理解&#xff0c;偏向锁、轻量级锁、重量级锁的本质。 对象内存布局 Hotspot虚拟机中&#xff0c;对象在内存中存储的布局可以分为三块区域:对象头(Header)、实例数据 (Instance Da…

【Sublime Text】| 02——常用插件安装及配置

系列文章目录 【Sublime Text】| 01——下载软件安装并注册 【Sublime Text】| 02——常用插件安装及配置 失败了也挺可爱&#xff0c;成功了就超帅。 文章目录 1. 汉化2. 更换颜色主题3. 更改编码插件—ConvertToUTF84. 对齐插件—Alignment5. 括号高亮插件—BracketHighligh…

win11修改本地hosts,自定义域名

目录 &#x1f9c8;1.打开指定目录 &#x1f95a;2.粘贴至桌面 &#x1f373;3.添加自己的域名和对应的ip地址 &#x1f37f;4.替换原来的hosts文件 1.打开指定目录&#x1f9c2;&#x1f9c2; 在C盘下打开 --------C:\Windows\System32\drivers\etc&#xff0c;找到hos…

众和策略:沪指跌0.91%险守2900点,半导体、金融等板块走低

8日早盘&#xff0c;两市股指低开低走&#xff0c;沪指一度失守2900点&#xff0c;深成指、创业板指跌约1%&#xff0c;科创50指数创前史新低。 到午间收盘&#xff0c;沪指跌0.91%报2902.4点&#xff0c;深成指跌1.17%&#xff0c;创业板指跌0.99%&#xff0c;科创50指数跌超…

vue3中使用elementplus中的el-tree-select,自定义显示名称label

<el-tree-select v-model"addPval" node-key"id" :data"menulists" :render-after-expand"false" :props"menuProps" /> <el-divider />let menuProps {//自定义labellabel: (data: { name: any; }) > {ret…

程序媛的mac修炼手册-- 终端(terminal)常用命令

「终端&#xff08;terminal&#xff09;」相当于macOS的一个 App &#xff0c;它的特殊之处是&#xff0c;它是管理其它App的App&#xff0c;操作主要通过命令行界面 (CLI) 。 相比于我们日常熟悉的用户界面&#xff08;User Interface&#xff0c;UI&#xff09;&#xff0c…

vue3 封裝一个常用固定按钮组件(添加、上传、下载、删除)

效果图 这个组件只有四个按钮&#xff0c;添加&#xff0c;上传、下载、删除&#xff0c;其中删除按钮的颜色默认是灰色&#xff0c;当表格有数据选中时再变成红色 实现 组件代码 <script lang"ts" setup> import { Icon } from /components/Icon/index im…

Qt应用-实现图像截取功能类似QQ上传头像截取功能

本文演示利用Qt实现图像截取功能类似QQ上传头像截取功能。 效果如下,通过移动中间的裁剪区域可以获得一张裁剪后的图片。 目录

OpenAI ChatGPT-4开发笔记2024-02:Chat之text generation之completions

API而已 大模型封装在库里&#xff0c;库放在服务器上&#xff0c;服务器放在微软的云上。我们能做的&#xff0c;仅仅是通过API这个小小的缝隙&#xff0c;窥探ai的奥妙。从程序员的角度而言&#xff0c;水平的高低&#xff0c;就体现在对openai的这几个api的理解程度上。 申…

【unity】基于Obi的绳长动态修改(ObiRopeCursor)

文章目录 一、在运行时改变绳子长度:ObiRopeCursor1.1 Cursor Mu&#xff08;光标μ&#xff09;1.2 Source Mu&#xff08;源μ&#xff09;1.3 Direction&#xff08;方向&#xff09; 一、在运行时改变绳子长度:ObiRopeCursor Obi提供了一个非常通用的组件来在运行时修改绳…

Vue3-39-路由-导航异常的检测 afterEatch 与 编程式导航之后的订阅动作

说明 本文主要是介绍一下 路由的后置守卫 afterEatch 的一个重要的作用 &#xff1a; 就是检测路由异常信息。 它的实现方式是 通过第三个参数来返回的。 而且&#xff0c;它的异常检测是全局的。导航的异常有以下三种类型&#xff1a; aborted : 在导航守卫中 被拦截并返回了…

苹果Find My查找芯片-伦茨科技ST17H6x支持苹果Find My认证

Apple「查找」Find My可通过庞大的“Apple Find My Network” 实现全球查找功能。无数iOS、iPadOS、macOS、watchOS激活设备与Find My 设备结合在一起&#xff0c;无需连接到Wi-Fi或者蜂窝网络&#xff0c;用户也可以给遗失的设备定位。对于任何iOS、iPadOS、macOS、watchOS设备…

Plantuml之nwdiag网络图语法介绍(二十九)

简介&#xff1a; CSDN博客专家&#xff0c;专注Android/Linux系统&#xff0c;分享多mic语音方案、音视频、编解码等技术&#xff0c;与大家一起成长&#xff01; 优质专栏&#xff1a;Audio工程师进阶系列【原创干货持续更新中……】&#x1f680; 优质专栏&#xff1a;多媒…

算法第十一天-组合总和Ⅳ

组合总和Ⅳ 题目要求 解题思路 来自[负雪明烛] 题目有个明显的提示&#xff1a;求组合的个数&#xff0c;而不是每个组合。如果是要求出每个组合&#xff0c;那么必须使用回溯法&#xff0c;保存所有路径。但是如果是组合个数&#xff0c;一般都应该想到[动态规划]的解法。 直…

*4.3 CUDA MEMORY TYPES

CUDA设备包含几种类型的内存&#xff0c;可以帮助程序员提高计算到全局内存的访问率&#xff0c;从而实现高执行速度。图4.6显示了这些CUDA设备内存。全局内存和恒定内存出现在图片的底部。主机可以通过调用API函数来写入&#xff08;W&#xff09;和读取&#xff08;R&#xf…

Python私有变量的定义与访问

class Student():def __init__(self, name, age):self.name nameself.age ageself.__score 0def marking(self, score):if score < 0:return 分数不能为0self.__score scoreprint(self.name 同学本次得分是: str(self.__score)) def __talk(self): # 私有的类可通过在…

Python爬虫-爬取豆瓣Top250电影信息

&#x1f388; 博主&#xff1a;一只程序猿子 &#x1f388; 博客主页&#xff1a;一只程序猿子 博客主页 &#x1f388; 个人介绍&#xff1a;爱好(bushi)编程&#xff01; &#x1f388; 创作不易&#xff1a;喜欢的话麻烦您点个&#x1f44d;和⭐&#xff01; &#x1f388;…

Wargames与bash知识12

Wargames与bash知识12 Bandit20 关卡提示&#xff1a; 主目录中有一个setuid二进制文件&#xff0c;它执行以下操作&#xff1a;它在您指定为命令行参数的端口上连接到localhost。然后&#xff0c;它从连接中读取一行文本&#xff0c;并将其与前一级别的密码&#xff08;band…