前言
本系列将依托赵虚左老师的ROS课程,写下自己的一些心得与笔记。
课程链接:https://www.bilibili.com/video/BV1Ci4y1L7ZZ
讲义链接:http://www.autolabor.com.cn/book/ROSTutorials/index.html
文章可能存在疏漏的地方,恳请大家指出。
保证 ROS 程序的可移植性
ros_control:是一组软件包,它包含了控制器接口,控制器管理器,传输和硬件接口。ros_control 是一套机器人控制的中间件,是一套规范,不同的机器人平台只要按照这套规范实现,那么就可以保证 与ROS 程序兼容,通过这套规范,实现了一种可插拔的架构设计,大大提高了程序设计的效率与灵活性。
承上,运动控制基本流程:
两轮差速配置
<robot name="my_car_move" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:macro name="joint_trans" params="joint_name">
<transmission name="${joint_name}_trans">
<type>transmission_interface/SimpleTransmissiontype>
<joint name="${joint_name}">
<hardwareInterface>hardware_interface/VelocityJointInterfacehardwareInterface>
joint>
<actuator name="${joint_name}_motor">
<hardwareInterface>hardware_interface/VelocityJointInterfacehardwareInterface>
<mechanicalReduction>1mechanicalReduction>
actuator>
transmission>
xacro:macro>
<xacro:joint_trans joint_name="left_wheel2base_link" />
<xacro:joint_trans joint_name="right_wheel2base_link" />
<gazebo>
<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>DebugrosDebugLevel>
<publishWheelTF>truepublishWheelTF>
<robotNamespace>/robotNamespace>
<publishTf>1publishTf>
<publishWheelJointState>truepublishWheelJointState>
<alwaysOn>truealwaysOn>
<updateRate>100.0updateRate>
<legacyMode>truelegacyMode>
<leftJoint>left_wheel2base_linkleftJoint>
<rightJoint>right_wheel2base_linkrightJoint>
<wheelSeparation>${base_link_radius * 2}wheelSeparation>
<wheelDiameter>${wheel_radius * 2}wheelDiameter>
<broadcastTF>1broadcastTF>
<wheelTorque>30wheelTorque>
<wheelAcceleration>1.8wheelAcceleration>
<commandTopic>cmd_velcommandTopic>
<odometryFrame>odomodometryFrame>
<odometryTopic>odomodometryTopic>
<robotBaseFrame>base_footprintrobotBaseFrame>
plugin>
gazebo>
robot>
依据驱动轮的xacro文件,将此处的joint名称改为驱动轮关节的名称.
<xacro:joint_trans joint_name="left_wheel2base_link" />
<xacro:joint_trans joint_name="right_wheel2base_link" />
同理,此处也要进行修改
<leftJoint>left_wheel2base_linkleftJoint>
<rightJoint>right_wheel2base_linkrightJoint>
车轮间距与车轮直径也需修改
<wheelSeparation>${base_link_radius * 2}wheelSeparation>
<wheelDiameter>${wheel_radius * 2}wheelDiameter>
<robot name="my_car_camera" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="my_head.urdf.xacro" />
<xacro:include filename="my_base.urdf.xacro" />
<xacro:include filename="my_camera.urdf.xacro" />
<xacro:include filename="my_laser.urdf.xacro" />
<xacro:include filename="move.urdf.xacro" />
robot>
<launch>
<param name="robot_description" command="$(find xacro)/xacro $(find demo02_urdf_gazebo)/urdf/xacro/my_base_camera_laser.urdf.xacro" />
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(find demo02_urdf_gazebo)/worlds/hello.world" />
include>
<node pkg="gazebo_ros" type="spawn_model" name="model" args="-urdf -model mycar -param robot_description" />
launch>
雷达仿真基本流程:
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
<gazebo reference="laser">
<sensor type="ray" name="rplidar">
<pose>0 0 0 0 0 0pose>
<visualize>truevisualize>
<update_rate>5.5update_rate>
<ray>
<scan>
<horizontal>
<samples>360samples>
<resolution>1resolution>
<min_angle>-3min_angle>
<max_angle>3max_angle>
horizontal>
scan>
<range>
<min>0.10min>
<max>30.0max>
<resolution>0.01resolution>
range>
<noise>
<type>gaussiantype>
<mean>0.0mean>
<stddev>0.01stddev>
noise>
ray>
<plugin name="gazebo_rplidar" filename="libgazebo_ros_laser.so">
<topicName>/scantopicName>
<frameName>laserframeName>
plugin>
sensor>
gazebo>
robot>
重点:
<gazebo reference="laser">
<topicName>/scantopicName>
<frameName>laserframeName>
<robot name="my_car_camera" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="my_head.urdf.xacro" />
<xacro:include filename="my_base.urdf.xacro" />
<xacro:include filename="my_camera.urdf.xacro" />
<xacro:include filename="my_laser.urdf.xacro" />
<xacro:include filename="move.urdf.xacro" />
<xacro:include filename="my_sensors_laser.urdf.xacro" />
robot>
gazebo的launch文件与之前一致
rviz的launch文件如下:
<launch>
<param name="robot_description" command="$(find xacro)/xacro $(find urdf02_gazebo)/urdf/xacro/car.urdf.xacro" />
<node pkg = "rviz" type = "rviz" name="rviz" args="-d $(find urdf01_rviz)/config/demo01.rviz"/>
<node pkg="joint_state_publisher" type="joint_state_publisher" name="joint_state_publisher" />
<node pkg="robot_state_publisher" type="robot_state_publisher" name="robot_state_publisher" />
launch>
摄像头仿真基本流程:
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
<gazebo reference="camera">
<sensor type="camera" name="camera_node">
<update_rate>30.0update_rate>
<camera name="head">
<horizontal_fov>1.3962634horizontal_fov>
<image>
<width>1280width>
<height>720height>
<format>R8G8B8format>
image>
<clip>
<near>0.02near>
<far>300far>
clip>
<noise>
<type>gaussiantype>
<mean>0.0mean>
<stddev>0.007stddev>
noise>
camera>
<plugin name="gazebo_camera" filename="libgazebo_ros_camera.so">
<alwaysOn>truealwaysOn>
<updateRate>0.0updateRate>
<cameraName>/cameracameraName>
<imageTopicName>image_rawimageTopicName>
<cameraInfoTopicName>camera_infocameraInfoTopicName>
<frameName>cameraframeName>
<hackBaseline>0.07hackBaseline>
<distortionK1>0.0distortionK1>
<distortionK2>0.0distortionK2>
<distortionK3>0.0distortionK3>
<distortionT1>0.0distortionT1>
<distortionT2>0.0distortionT2>
plugin>
sensor>
gazebo>
robot>
重点
<gazebo reference="camera">
<sensor type="camera" name="camera_node">
<frameName>cameraframeName>
<robot name="my_car_camera" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="my_head.urdf.xacro" />
<xacro:include filename="my_base.urdf.xacro" />
<xacro:include filename="my_camera.urdf.xacro" />
<xacro:include filename="my_laser.urdf.xacro" />
<xacro:include filename="move.urdf.xacro" />
<xacro:include filename="my_sensors_camara.urdf.xacro" />
robot>
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
<gazebo reference="kinect link名称">
<sensor type="depth" name="camera">
<always_on>truealways_on>
<update_rate>20.0update_rate>
<camera>
<horizontal_fov>${60.0*PI/180.0}horizontal_fov>
<image>
<format>R8G8B8format>
<width>640width>
<height>480height>
image>
<clip>
<near>0.05near>
<far>8.0far>
clip>
camera>
<plugin name="kinect_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<cameraName>cameracameraName>
<alwaysOn>truealwaysOn>
<updateRate>10updateRate>
<imageTopicName>rgb/image_rawimageTopicName>
<depthImageTopicName>depth/image_rawdepthImageTopicName>
<pointCloudTopicName>depth/pointspointCloudTopicName>
<cameraInfoTopicName>rgb/camera_infocameraInfoTopicName>
<depthImageCameraInfoTopicName>depth/camera_infodepthImageCameraInfoTopicName>
<frameName>kinect link名称frameName>
<baseline>0.1baseline>
<distortion_k1>0.0distortion_k1>
<distortion_k2>0.0distortion_k2>
<distortion_k3>0.0distortion_k3>
<distortion_t1>0.0distortion_t1>
<distortion_t2>0.0distortion_t2>
<pointCloudCutoff>0.4pointCloudCutoff>
plugin>
sensor>
gazebo>
robot>
<robot name="my_car_camera" xmlns:xacro="http://wiki.ros.org/xacro">
<xacro:include filename="my_head.urdf.xacro" />
<xacro:include filename="my_base.urdf.xacro" />
<xacro:include filename="my_camera.urdf.xacro" />
<xacro:include filename="my_laser.urdf.xacro" />
<xacro:include filename="move.urdf.xacro" />
<xacro:include filename="my_sensors_kinect.urdf.xacro" />
robot>
原因:在kinect中图像数据与点云数据使用了两套坐标系统,且两套坐标系统位姿并不一致。
解决:
1.在插件中为kinect设置坐标系,修改配置文件的
标签内容:
<frameName>support_depthframeName>
2.发布新设置的坐标系到kinect连杆的坐标变换关系,在启动rviz的launch中,添加:
<node pkg="tf2_ros" type="static_transform_publisher" name="static_transform_publisher" args="0 0 0 -1.57 0 -1.57 /support /support_depth" />