源码编译的Moveit!环境去编译auboi5工程并驱动aubo机械臂实体
环境
ubuntu20.04、ros noetic、源码编译的Moveit!环境、aubo i5机械臂
配置aubo的config
在aubo官网下载了源码并在Moveit!下编译后,会出现aubo_i5_moveit_config文件夹,我们这里还需要另外配置它的config,具体配置的地方如图所示(aubo_i5_moveit_config文件夹下的config下):
根据aubo的github官网的aubo_i5_moveit_config文件夹下的config,对比你自己的config文件补齐缺的文件,千万不要一键全部替换,缺什么补什么
对应的launch文件也要补齐,aubo_i5_moveit_config文件夹下的launch下:
根据aubo的github官网的aubo_i5_moveit_config文件夹下的launch,对比你自己的launch文件补齐缺的文件,千万不要一键全部替换,缺什么补什么
启动aubo rviz报错
执行命令
roslaunch aubo_i5_moveit_config moveit_planning_execution.launch robot_ip:=127.0.0.1
rviz还么起来,直接报错:
RLException: unused args [config] for include of [/home/cxh/moveit_ws/src/aubo_i5_moveit_config/launch/moveit_rviz.launch]
The traceback for the exception was written to the log file
这个错误信息表明,在运行 ROS 的 launch 文件时,遇到了未使用的参数 config。具体来说,错误发生在加载 /home/cxh/moveit_ws/src/aubo_i5_moveit_config/launch/moveit_rviz.launch 文件时,传递了一个名为 config 的参数,但该参数在 moveit_rviz.launch 文件中未被使用或识别。
解决方案
修改moveit_rviz.launch文件,内容如下:
<launch>
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
<arg name="config" default="false" />
<arg unless="$(arg config)" name="command_args" value="" />
<arg if="$(arg config)" name="command_args" value="-d $(find aubo_i5_moveit_config)/launch/moveit.rviz" />
<node name="$(anon rviz)" launch-prefix="$(arg launch_prefix)" pkg="rviz" type="rviz" respawn="false"
args="$(arg command_args)" output="screen">
<rosparam command="load" file="$(find aubo_i5_moveit_config)/config/kinematics.yaml"/>
</node>
</launch>
再重新编译启动rviz
source devel/setup.bash
catkin build
roslaunch aubo_i5_moveit_config moveit_planning_execution.launch robot_ip:=127.0.0.1
点击rviz界面,执行机械臂运动到目标home位置时报错:
[ERROR] [1723538618.245612518, 1251.713000000]: Unable to identify any set of controllers that can actuate the specified joints: [ foreArm_joint shoulder_joint upperArm_joint wrist1_joint wrist2_joint wrist3_joint ]
[ERROR] [1723538618.245708602, 1251.713000000]: Known controllers and their joints:
这个错误表明在控制机械臂时,MoveIt! 无法找到能够控制指定关节的控制器集合。错误中提到的关节包括 foreArm_joint、shoulder_joint、upperArm_joint、wrist1_joint、wrist2_joint 和 wrist3_joint。
解决办法
修改move_group.launch,修改后整个launch文件内容如下:
<launch>
<include file="$(find aubo_i5_moveit_config)/launch/planning_context.launch" />
<!-- GDB Debug Option -->
<arg name="debug" default="false" />
<arg unless="$(arg debug)" name="launch_prefix" value="" />
<arg if="$(arg debug)" name="launch_prefix"
value="gdb -x $(find aubo_i5_moveit_config)/launch/gdb_settings.gdb --ex run --args" />
<!-- Verbose Mode Option -->
<arg name="info" default="$(arg debug)" />
<arg unless="$(arg info)" name="command_args" value="" />
<arg if="$(arg info)" name="command_args" value="--debug" />
<!-- move_group settings -->
<arg name="allow_trajectory_execution" default="true"/>
<arg name="fake_execution" default="false"/>
<arg name="max_safe_path_cost" default="1"/>
<arg name="jiggle_fraction" default="0.05" />
<arg name="publish_monitored_planning_scene" default="true"/>
<arg name="capabilities" default=""/>
<arg name="disable_capabilities" default=""/>
<!-- load these non-default MoveGroup capabilities (space seperated) -->
<!--
<arg name="capabilities" value="
a_package/AwsomeMotionPlanningCapability
another_package/GraspPlanningPipeline
" />
-->
<!-- inhibit these default MoveGroup capabilities (space seperated) -->
<!--
<arg name="disable_capabilities" value="
move_group/MoveGroupKinematicsService
move_group/ClearOctomapService
" />
-->
<!-- Planning Functionality -->
<include ns="move_group" file="$(find aubo_i5_moveit_config)/launch/planning_pipeline.launch.xml">
<arg name="pipeline" value="ompl" />
</include>
<!-- Trajectory Execution Functionality -->
<include ns="move_group" file="$(find aubo_i5_moveit_config)/launch/trajectory_execution.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_manage_controllers" value="true" />
<arg name="moveit_controller_manager" value="aubo_i5" unless="$(arg fake_execution)"/>
<arg name="moveit_controller_manager" value="fake" if="$(arg fake_execution)"/>
</include>
<!-- Sensors Functionality -->
<include ns="move_group" file="$(find aubo_i5_moveit_config)/launch/sensor_manager.launch.xml" if="$(arg allow_trajectory_execution)">
<arg name="moveit_sensor_manager" value="aubo_i5" />
</include>
<!-- Start the actual move_group node/action server -->
<node name="move_group" launch-prefix="$(arg launch_prefix)" pkg="moveit_ros_move_group" type="move_group" respawn="false" output="screen" args="$(arg command_args)">
<!-- Set the display variable, in case OpenGL code is used internally -->
<env name="DISPLAY" value="$(optenv DISPLAY :0)" />
<param name="allow_trajectory_execution" value="$(arg allow_trajectory_execution)"/>
<param name="max_safe_path_cost" value="$(arg max_safe_path_cost)"/>
<param name="jiggle_fraction" value="$(arg jiggle_fraction)" />
<param name="capabilities" value="$(arg capabilities)"/>
<param name="disable_capabilities" value="$(arg disable_capabilities)"/>
<!-- Publish the planning scene of the physical robot so that rviz plugin can know actual robot -->
<param name="planning_scene_monitor/publish_planning_scene" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_geometry_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_state_updates" value="$(arg publish_monitored_planning_scene)" />
<param name="planning_scene_monitor/publish_transforms_updates" value="$(arg publish_monitored_planning_scene)" />
</node>
</launch>
再重新编译并启动
source devel/setup.bash
catkin build
roslaunch aubo_i5_moveit_config moveit_planning_execution.launch robot_ip:=127.0.0.1
这次发现可以正常运行了
与实体aubo机械臂相连并通过rviz驱动实体
新建一个终端运行ifconfig命令
这里可以看到我们的电脑ip是115.25.41.37,掩码:255.255.255.0 网关:115.25.41.255
再找一根网线用来连接机械臂和自己的这台主机,在通信连接之前,多次执行ifconfig指令,然后迅速拔下自己主机原先网线,吧连往机械臂的网线另一端插入到对应网口,在机械臂的示教器上ping通
点开示教器的网络配置,上面的IP地址是机械臂的地址,自己随机定一个,只改最后一个字段即可我自己的换成33,然后网络调试下写自己的主机ip,最后点ping,如果ping通就会有下面的时间信息,前五行都是时间信息。
此时你也可以在主机上ping机械臂
ping 115.25.41.33
会发现也是通的,表明通信成功
这样就可以在你的电脑上启动机械臂rviz
source devel/setup.bash
roslaunch aubo_i5_moveit_config moveit_planning_execution.launch robot_ip:=115.25.41.33
通过先在rviz上plan机械臂运动,然后再execute实体运动,因为仿真环境运动没问题,实体就不会出意外。