|
| 1 | +.. _ros2-interfaces: |
| 2 | + |
| 3 | +================= |
| 4 | +ROS 2 Interfaces |
| 5 | +================= |
| 6 | + |
| 7 | +The purpose of this page is to document all the ROS 2 interfaces available in ArduPilot. |
| 8 | +Content is organized by functional area the data is used. |
| 9 | + |
| 10 | +Sensors |
| 11 | +======= |
| 12 | + |
| 13 | +ArduPilot exposes "sensor" type data over DDS, that usually corresponds to a physical component, or some filterered version of it. |
| 14 | + |
| 15 | +.. raw:: html |
| 16 | + |
| 17 | + <table border="1" class="docutils"> |
| 18 | + <tbody> |
| 19 | + <tr> |
| 20 | + <th>Topic Name</th> |
| 21 | + <th>Topic Type</th> |
| 22 | + <th>Description</th> |
| 23 | + </tr> |
| 24 | + <tr> |
| 25 | + <td>ap/navsat/navsat0</td> |
| 26 | + <td>sensor_msgs/msg/NavSatFix</td> |
| 27 | + <td>This is the reported GPS sensor position from the GPS subsystem. |
| 28 | + TODO It will include a frame ID as instance number</td> |
| 29 | + </tr> |
| 30 | + <tr> |
| 31 | + <td>ap/battery</td> |
| 32 | + <td>sensor_msgs/msg/BatteryState</td> |
| 33 | + <td>This sends the battery state for each enabled battery. |
| 34 | + The battery instance is available in the frame ID. |
| 35 | + Each enabled battery will be have data published. |
| 36 | + </tr> |
| 37 | + <tr> |
| 38 | + <td>ap/imu/experimental/data</td> |
| 39 | + <td>sensor_msgs/msg/IMU</td> |
| 40 | + <td>This is the high rate IMU data from the IMU that is currently used in the EKF.</td> |
| 41 | + </tr> |
| 42 | + <tr> |
| 43 | + <td>ap/airspeed</td> |
| 44 | + <td>geometry_msgs/msg/Vector3Stamped</td> |
| 45 | + <td>This is the 3D airspeed estimate of the vehicle in body frame.</td> |
| 46 | + </tr> |
| 47 | + </tbody> |
| 48 | + </table> |
| 49 | + |
| 50 | +Pose, Rates, and Coordinates |
| 51 | +============================ |
| 52 | + |
| 53 | +.. raw:: html |
| 54 | + |
| 55 | + <table border="1" class="docutils"> |
| 56 | + <tbody> |
| 57 | + <tr> |
| 58 | + <th>Topic Name</th> |
| 59 | + <th>Topic Type</th> |
| 60 | + <th>Description</th> |
| 61 | + </tr> |
| 62 | + <tr> |
| 63 | + <td>ap/gps_global_origin/filtered</td> |
| 64 | + <td>geographic_msgs/msg/GeoPointStamped</td> |
| 65 | + <td>This is the filtered AHRS's inertial navigation origin. This is NOT the same ask the HOME location. |
| 66 | + </tr> |
| 67 | + <tr> |
| 68 | + <td>ap/twist/filtered</td> |
| 69 | + <td>geometry_msgs/msg/TwistStamped</td> |
| 70 | + <td>This is the filtered AHRS's velocity in the local ENU frame relative to home.</td> |
| 71 | + </tr> |
| 72 | + <tr> |
| 73 | + <td>ap/geopose/filtered</td> |
| 74 | + <td>geographic_msgs/msg/GeoPoseStamped</td> |
| 75 | + <td>This is the filtered AHRS's pose (position+orientation) in global coordinates</td> |
| 76 | + </tr> |
| 77 | + <tr> |
| 78 | + <td>ap/tf_static</td> |
| 79 | + <td>tf2_msgs/msg/TFMessage</td> |
| 80 | + <td>AP broadcasts its known static transforms on this topic. |
| 81 | + The transforms include the GPS sensor offsets relative to the vehicle origin.</td> |
| 82 | + </tr> |
| 83 | + </tbody> |
| 84 | + </table> |
| 85 | + |
| 86 | +Time |
| 87 | +==== |
| 88 | + |
| 89 | +.. raw:: html |
| 90 | + |
| 91 | + <table border="1" class="docutils"> |
| 92 | + <tbody> |
| 93 | + <tr> |
| 94 | + <th>Topic Name</th> |
| 95 | + <th>Topic Type</th> |
| 96 | + <th>Description</th> |
| 97 | + </tr> |
| 98 | + <tr> |
| 99 | + <td>ap/time</td> |
| 100 | + <td>builtin_interface/msg/Time</td> |
| 101 | + <td>This sends time from AP's real time clock.</td> |
| 102 | + </tr> |
| 103 | + <tr> |
| 104 | + <td>ap/clock</td> |
| 105 | + <td>rosgraph_msgs/msg/Clock</td> |
| 106 | + <td>This sends time from AP's real time clock in a format suitable for aligning ROS time of a companion computer.</td> |
| 107 | + </tr> |
| 108 | + </tbody> |
| 109 | + </table> |
| 110 | + |
| 111 | +Control |
| 112 | +======= |
| 113 | + |
| 114 | +The control interfaces are how a companion computer can command the autopilot to move |
| 115 | +either it's control surfaces, motors, or tell the autopilot to control to a setpoint position, velocity, acceleration. |
| 116 | +Control includes the high level navigation objectives. |
| 117 | + |
| 118 | +.. raw:: html |
| 119 | + |
| 120 | + <table border="1" class="docutils"> |
| 121 | + <tbody> |
| 122 | + <tr> |
| 123 | + <th>Topic Name</th> |
| 124 | + <th>Topic Type</th> |
| 125 | + <th>Description</th> |
| 126 | + </tr> |
| 127 | + <tr> |
| 128 | + <td>ap/joy</td> |
| 129 | + <td>sensor_msgs/msg/Joy</td> |
| 130 | + <td>Receive joystick commands that override the RC input.</td> |
| 131 | + </tr> |
| 132 | + <tr> |
| 133 | + <td>ap/cmd_vel</td> |
| 134 | + <td>geometry_msgs/msg/TwistStamped</td> |
| 135 | + <td>Receive REP-147 velocity commands. |
| 136 | + Some vehicles support body frame while others support earth frame. |
| 137 | + </td> |
| 138 | + </tr> |
| 139 | + <tr> |
| 140 | + <td>ap/cmd_gps_pose</td> |
| 141 | + <td>geometry_msgs/msg/TwistStamped</td> |
| 142 | + <td>Receive REP-147 "High level goal". |
| 143 | + This message is called "GlobalPosition" in REP-147. |
| 144 | + Consult the source code to determine which fields are supported on which vehicles. |
| 145 | + </td> |
| 146 | + </tr> |
| 147 | + </tbody> |
| 148 | + </table> |
| 149 | + |
| 150 | +Commands |
| 151 | +======== |
| 152 | + |
| 153 | +ArduPilot exposes service servers for the following purposes: |
| 154 | + |
| 155 | +* Pre-arm check |
| 156 | +* Arming |
| 157 | +* Changing modes |
| 158 | +* Takeoff (copter only) |
| 159 | + |
| 160 | +Odometry |
| 161 | +======== |
| 162 | + |
| 163 | +Ardupilot may not have a good estimate of where it relative to where it started moving. |
| 164 | +A companion computer can interface with sensors that provide odometry, which is the computation of the dynamic transform |
| 165 | +from the ``odom`` frame to the ``base_link`` frame. This data is fed into ArduPilot's ``AP_VisualOdom`` library. |
| 166 | +This data may come from visual sensors, however other technologies such as radar and lidar can |
| 167 | +also provide odometry data. Regardless of the method of odometry, |
| 168 | +ArduPilot has a single ROS interface to receive it. |
| 169 | + |
| 170 | +This data typically comes from a `TF2 Transfrom Tree <https://docs.ros.org/en/humble/Tutorials/Intermediate/Tf2/Tf2-Main.html>`_. |
| 171 | +For more information on the coordinate systems used, review `ROS REP-105 <https://www.ros.org/reps/rep-0105.html>`_. |
| 172 | + |
| 173 | +.. raw:: html |
| 174 | + |
| 175 | + <table border="1" class="docutils"> |
| 176 | + <tbody> |
| 177 | + <tr> |
| 178 | + <th>Topic Name</th> |
| 179 | + <th>Topic Type</th> |
| 180 | + <th>Description</th> |
| 181 | + </tr> |
| 182 | + <tr> |
| 183 | + <td>ap/tf</td> |
| 184 | + <td>tf2_msgs/msg/TFMessage</td> |
| 185 | + <td>Receive the odometry dynamic transform on the normal tf2 dynamic transform topic.</td> |
| 186 | + </tr> |
| 187 | + <tr> |
| 188 | + </tbody> |
| 189 | + </table> |
| 190 | + |
| 191 | + |
| 192 | +Configuring Interfaces at Compile Time |
| 193 | +====================================== |
| 194 | + |
| 195 | +ArduPilot strives to only consume the resources it needs. |
| 196 | +The DDS interface is no exception. |
| 197 | + |
| 198 | +Every topic and service can be individually enabled or disabled |
| 199 | +at compile time. See |
| 200 | +:ref:`common-oem-customizations`. |
| 201 | + |
| 202 | +Refer to the `AP_DDS_Config.h <https://github.com/ArduPilot/ardupilot/blob/master/libraries/AP_DDS/AP_DDS_config.h>`_ |
| 203 | +file on what is exposed. |
| 204 | + |
| 205 | +Additionally, publish rates form ArduPilot also all indivually configurable at compile time. |
| 206 | + |
| 207 | +When deploying ArduPilot on a resource constrained autopilot, developers |
| 208 | +can disable interfaces they do not use and tune data rates to only |
| 209 | +what their applications need. |
| 210 | + |
| 211 | +Adding New Interfaces |
| 212 | +===================== |
| 213 | + |
| 214 | +ArduPilot's DDS interface is designed to be extensible. |
| 215 | +Interfaces for pub/sub and services are easily added. |
| 216 | + |
| 217 | +If the interfaces are generic, consider contributing them to ArduPilot. |
| 218 | +Custom application-specific interfaces are also easy to add and maintain |
| 219 | +on private forks of ArduPilot. |
| 220 | + |
| 221 | +Interfaces that use custom messages that aren't already used commonly in |
| 222 | +the ROS 2 ecosystem are typically added with an ``experimental`` designator. |
| 223 | + |
| 224 | + |
| 225 | +ABI Stability Guarantees |
| 226 | +======================== |
| 227 | + |
| 228 | +ArduPilot's DDS interface is intended to be ABI stable within an ArduPilot minor release. |
| 229 | +Common interfaces such as ``NavSatFix`` are unlikely to change, however experimental interfaces |
| 230 | +such as ``IMU`` may change, and are denoted with the ``experimental`` topic prefix. |
| 231 | +In extenuating circumstances, non-experimental topics may require bugfixes that |
| 232 | +change behavior, however message definitions will be kept compatible. |
| 233 | + |
| 234 | +Because the ROS way of updating messages it to not change messages |
| 235 | +within a ROS release, many tools do not cope well with messages. |
| 236 | +Different versions of the message between an autopilot and companion computer |
| 237 | +can lead to receiving junk data without any errors, or cryptic serialization |
| 238 | +errors. Thus, ArduPilot will do it's best to avoid changing messages. |
| 239 | +If breaking changes are required, the ArduPilot release notes will make that clear. |
| 240 | + |
| 241 | +Developers should not expect ABI stability on ``exerimental`` interfaces. |
| 242 | + |
| 243 | +Because ArduPilot does not follow the same release timeline as ROS 2, and |
| 244 | +the development team for the ROS interface still in its early stages, |
| 245 | +ArduPilot does not yet support a stable ABI across multiple ROS distributions. |
| 246 | +The current ROS version supported is ``humble``. |
0 commit comments