本章内容:Sunray无人车控制模块介绍与使用方式
控制模块路径与主要文件:
编译控制模块
catkin_make --source General_Module/sunray_ugv_control --build build/sunray_ugv_control
在使用前需要了解Sunray的控制模块中的几种模式
- INIT:该模式在无人车处于无指令状态,初始运行时将处于该模式
- HOLD:该模式在无人车处于静止,此模式下无人车速度为0
- POS_CONTROL_ENU:惯性系位置控制, 需要配合desired_pos和desired_yaw使用
- VEL_CONTROL_ENU:惯性系速度控制, 需要配合desired_vel和desired_yaw使用
- VEL_CONTROL_BODY:惯性系速度控制, 需要配合desired_vel和desired_yaw使用
- Point_Control_with_Astar:惯性系速度控制, 需要配合desired_pos和desired_yaw使用
重要参数说明
- geo_fence:地理围栏,包含x、y、z三个方向的最大最小值
- enable_astar:无人车是否启用A*避障参数
- laser_topic:雷达话题相关参数
- map/resolution:地图分辨率参数
- map/inflate:地图膨胀系数参数
- location_source:定位源参数
消息说明
无人车的消息文件
- UGVControlCMD.msg
复制代码## 自定义消息:无人车控制指令 ## 消息header std_msgs/Header header ## 控制命令 uint8 cmd ## 控制命令枚举 uint8 INIT=0 ## 初始化,不做任何控制 uint8 HOLD=1 ## 当前点停止 uint8 POS_CONTROL_ENU=2 ## 惯性系位置控制, 需要配合desired_pos和desired_yaw使用 uint8 VEL_CONTROL_ENU=3 ## 惯性系速度控制, 需要配合desired_vel和desired_yaw使用 uint8 VEL_CONTROL_BODY=4 ## 车体系速度控制, 需要配合desired_vel和desired_yaw使用 uint8 Point_Control_with_Astar=5 ## Astar避障控制, 需要配合desired_pos和desired_yaw使用 uint8 POS_VEL_CONTROL_ENU= 6 ## 偏航角类型 0 角速度 1 角度(需要有定位支持) uint8 yaw_type ## 控制命令期望值 float32[2] desired_pos ## [m] float32[2] desired_vel ## [m/s] float32 desired_yaw ## [rad] float32 angular_vel ## [rad/s]
- UGVState.msg
复制代码## 自定义消息:无人车状态 ## 消息header std_msgs/Header header ## 无人车基本信息 uint8 ugv_id ## 无人车编号 bool connected ## 无人车连接状态 ## 无人车电池状态 float32 battery_state ## [V] float32 battery_percentage ## [0-1] ## 无人车里程计信息 uint8 location_source ## 无人车定位来源 bool odom_valid ## 里程计是否有效 ## 无人车状态信息 float32[2] position ## [m] float32[2] velocity ## [m/s] float32 yaw ## [rad] float32[3] attitude ## [rad] geometry_msgs/Quaternion attitude_q ## 四元数 ## 无人车控制命令及目标设定值 uint8 control_mode float32[2] pos_setpoint ## [m] 位置控制目标点 float32[2] vel_setpoint ## [m/s] 速度控制目标 float32 yaw_setpoint ## [rad] 姿态控制目标 ## 无人车参数信息 float32[2] home_pos ## 原点 float32 home_yaw ## 原点 float32[2] hover_pos ## 悬停点 float32 hover_yaw ## 悬停点
接口说明
在Sunray的控制模块中通过订阅话题实现对无人车状态和任务的控制
- sunray/UGVControlCMD
消息定义:Sunray/General_Module/sunray_common/sunray_msgs/msg/UGVControlCMD.msg
消息说明:该消息用于对控制模块中设置小车状态参数,详细功能请阅读消息定义
- 例:设置小车目标位置与速度以及偏航角、角速度
复制代码rostopic pub /ugv1/sunray_ugv/ugv_control_cmd sunray_msgs/UGVControlCMD "header: seq: 0 stamp: {secs: 0, nsecs: 0} frame_id: '' cmd: 0 yaw_type: 0 desired_pos: [0.0, 0.0] desired_vel: [0.0, 0.0] desired_yaw: 0.0 angular_vel: 0.0"
# 启动节点
roslaunch sunray_ugv_control ugv_control_exp.launch
## 启动仿真加载模型
roslaunch sunray_simulator sunray_sim_1ugv.launch
# 启动节点
roslaunch sunray_ugv_control ugv_control_sim.launch
# 启动节点
roslaunch sunray_ugv_control ugv_terminal_control.launch