# 应用程序接口 (API) 我们为Kerloud Autocar系列提供用于开发的开源API,并有C++、Python或其他语言的版本可选用,详细内容会在本章节持续更新。 ## 1. ROS API (C++) ROS(Robot Operating System)中的 API 基于PX4 社区的官方[MAVROS 包](http://wiki.ros.org/mavros)实现。 我们在维护的库为: - mavros(dev_rover 分支):[https ://github.com/cloudkernel-tech/mavros](https://github.com/cloudkernel-tech/mavros) - mavlink(dev_rover 分支):[https ://github.com/cloudkernel-tech/mavlink-gdp-release](https://github.com/cloudkernel-tech/mavlink-gdp-release) - 使用 ROS C++ API(dev_rover 分支)的offboard 例程:[https ://github.com/cloudkernel-tech/offboard_demo](https://github.com/cloudkernel-tech/offboard_demo) ### 1.1 Topics #### (1)~mavros/setpoint_position/local, ~mavros/setpoint_position/global 本话题用于发布在本地或全局坐标系下的航点位置信息,陆地车、多旋翼模式下通用。需注意,ROS层使用的参考坐标系为ENU,而自驾仪使用的则是NED,消息类型分别为[geometry_msgs/PoseStamped](http://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html)和[mavros_msgs/GlobalPositionTarget](http://docs.ros.org/en/api/mavros_msgs/html/msg/GlobalPositionTarget.html)。 #### (2)~mavros/setpoint_velocity/cmd_vel_unstamped, ~mavros/setpoint_velocity/cmd_vel 这两个话题用于发布飞车在本地坐标系中的速度设定值,陆地车、多旋翼模式下通用,两个话题的唯一区别是速度信息是否携带时间戳。消息类型为[geometry_msgs/Twist](http://docs.ros.org/en/api/geometry_msgs/html/msg/Twist.html)。 #### (3)~mavros/setpoint_attitude/attitude, ~mavros/setpoint_attitude/thrust 这两个主题用于设置姿态和推力设定点。消息类型是[geometry_msgs/PoseStamped](http://docs.ros.org/en/api/geometry_msgs/html/msg/PoseStamped.html) 和[mavros_msgs/Thrust](http://docs.ros.org/en/api/mavros_msgs/html/msg/Thrust.html)。姿态推力直接输入车体的主推进油门控制,通过计算偏航角跟踪误差来生成转向伺服控制输入。 #### (4)~mavros/actuator_control 该话题可用于直接控制低级执行器,包括转向伺服和主电机。消息类型为[mavros_msgs/ActuatorControl](http://docs.ros.org/en/api/mavros_msgs/html/msg/ActuatorControl.html)。转向伺服和主电机的通道编号分别为 2 和 3。 ### 1.2 Services #### (1)~mavros/cmd/command 本服务用于在offboard模式下控制车体在前进和后退之间进行模式切换,消息类型为[mavros_msgs/CommandLong](http://docs.ros.org/en/api/mavros_msgs/html/srv/CommandLong.html)。它对应于[https://github.com/cloudkernel-tech/mavlink-gdp-release/blob/dev_rover/message_definitions/v1.0/common.xml](https://github.com/cloudkernel-tech/mavlink-gdp-release/blob/dev_rover/message_definitions/v1.0/common.xml) 中的自定义 mavlink 消息(mavlink::common::MAV_CMD::SET_ROVER_FORWARD_REVERSE_DRIVING)。 举例而言,如果我们想切换到前进,则必须使用以下设置来调用服务: mavros_msgs::CommandLong set_forward_driving_cmd; set_forward_driving_cmd.request.command (uint16_t)mavlink::common::MAV_CMD::SET_ROVER_FORWARD_REVERSE_DRIVING; set_forward_driving_cmd.request.confirmation = 0; set_forward_driving_cmd.request.param1 = 1.0f; 反过来实现后退: mavros_msgs::CommandLong set_backward_driving_cmd; set_backward_driving_cmd.request.command = (uint16_t)mavlink::common::MAV_CMD::SET_ROVER_FORWARD_REVERSE_DRIVING; set_backward_driving_cmd.request.confirmation = 0; set_backward_driving_cmd.request.param1 = 0.0f; ## 2.ROS API(python) 与 C++ 版的 ROS API 类似,ROS python API 也是基于我们维护的 mavros 和 mavlink 包实现的。仅有的区别是上文提到的所有话题和服务需通过python来使用。 我们在维护的库为: - mavros(dev_rover 分支):[https ://github.com/cloudkernel-tech/mavros](https://github.com/cloudkernel-tech/mavros) - mavlink(dev_rover 分支):[https ://github.com/cloudkernel-tech/mavlink-gdp-release](https://github.com/cloudkernel-tech/mavlink-gdp-release) - 使用 ROS python API(dev_rover 分支)的offboard控制示例:[https ://github.com/cloudkernel-tech/offboard_demo_python](https://github.com/cloudkernel-tech/offboard_demo_python) 代码将在使用教程章节进行讲解。为简洁起见,底层消息通信在Px4Controller类中进行处理,而面向用户编程用的友好API接口封装于Commander类中,部分API列举如下: - **move_position(x,y,z, BODY_FLU=False)**:请求车辆移动到 FLU 坐标系或 ENU 坐标系下定义的指定位置,忽略 z 通道。 - **move_velocity(vx,vy,vz, BODY_FLU=False)**:请求车辆在FLU 坐标系或 ENU 坐标系下以指定的速度移动,忽略 z 通道。 - **set_forward_driving()**:请求车辆前进,仅适用于姿态和执行器控制命令模式。 - **set_backward_driving()**:请求车辆向后移动,仅适用于姿态和执行器控制命令模式。 - **set_yaw_and_throttle()**:为车辆设置所需的偏航角和油门。 - **set_steering_servo_and_throttle()**:设置车辆的直接执行器控制,包括转向伺服和油门输入。 - **arm()**:请求解锁车辆。 - **disarm()**:请求锁定车辆。 - **return_home()**:请求车辆返航,为ENU坐标系下的原点。