i+=put_uint8_t_by_index(type,i,msg->payload);// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i+=put_uint8_t_by_index(autopilot,i,msg->payload);// Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i+=put_uint8_t_by_index(2,i,msg->payload);// MAVLink version
i+=put_uint8_t_by_index(type,i,msg->payload);// Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
i+=put_uint8_t_by_index(autopilot,i,msg->payload);// Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
i+=put_uint8_t_by_index(2,i,msg->payload);// MAVLink version
<description>Set the location the system should be heading towards (camera heads or
rotary wing aircraft).</description>
<paramindex="1">Empty</param>
<paramindex="2">Empty</param>
<paramindex="3">Empty</param>
<entryname="MAV_CMD_NAV_ROI"value="80">
<description>Sets the region of interest (ROI) for a sensor set or the
vehicle itself. This can then be used by the vehicles control
system to control the vehicle attitude and the attitude of various
sensors such as cameras.</description>
<paramindex="1">Region of intereset mode. (see MAV_ROI enum)</param>
<paramindex="2">Waypoint index/ target ID. (see MAV_ROI enum)</param>
<paramindex="3">ROI index (allows a vehicle to manage multiple ROI's)</param>
<paramindex="4">Empty</param>
<paramindex="5">Latitude</param>
<paramindex="6">Longitude</param>
<paramindex="7">Altitude</param>
<paramindex="5">x the location of the fixed ROI (see MAV_FRAME)</param>
<paramindex="6">y</param>
<paramindex="7">z</param>
</entry>
<entryname="MAV_CMD_NAV_PATHPLANNING"value="81">
<description>Control autonomous path planning on the MAV.</description>
<paramindex="1">0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning</param>
...
...
@@ -306,6 +310,18 @@
<entryname="MAV_DATA_STREAM_EXTRA2"value="11"><description>Dependent on the autopilot</description></entry>
<entryname="MAV_DATA_STREAM_EXTRA3"value="12"><description>Dependent on the autopilot</description></entry>
</enum>
<enumname="MAV_ROI">
<description> The ROI (region of interest) for the vehicle. This can be
be used by the vehicle for camera/vehicle attitude alignment (see
MAV_CMD_NAV_ROI).
</description>
<entryname="MAV_ROI_WPNEXT"value="0"><description>Point toward next waypoint.</description></entry>
<entryname="MAV_ROI_WPINDEX"value="1"><description>Point toward given waypoint.</description></entry>
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<fieldtype="uint8_t"name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<fieldtype="uint8_t"name="autopilot">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field>