MAV_CMD_DO_REPEAT_RELAY=182,/* Cycle a relay on and off for a desired number of cyles with a desired period. | Relay number | Cycle count | Cycle time (seconds, decimal) | Empty | Empty | Empty | Empty | */
MAV_CMD_DO_SET_SERVO=183,/* Set a servo to a desired PWM value. | Servo number | PWM (microseconds, 1000 to 2000 typical) | Empty | Empty | Empty | Empty | Empty | */
MAV_CMD_DO_REPEAT_SERVO=184,/* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. | Servo number | PWM (microseconds, 1000 to 2000 typical) | Cycle count | Cycle time (seconds) | Empty | Empty | Empty | */
MAV_CMD_DO_CONTROL_VIDEO=200,/* Control onboard camera system. | Camera ID (-1 for all) | Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw | Transmission mode: 0: video stream, >0: single images every n seconds (decimal) | Recording: 0: disabled, 1: enabled compressed, 2: enabled raw | Empty | Empty | Empty | */
MAV_CMD_DO_CONTROL_VIDEO=200,/* Control onboard camera capturing. | Camera ID (-1 for all) | Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw | Transmission mode: 0: video stream, >0: single images every n seconds (decimal) | Recording: 0: disabled, 1: enabled compressed, 2: enabled raw | Empty | Empty | Empty | */
MAV_CMD_DO_SET_ROI=201,/* 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 devices such as cameras. | Region of interest mode. (see MAV_ROI enum) | Waypoint index/ target ID. (see MAV_ROI enum) | ROI index (allows a vehicle to manage multiple cameras etc.) | Empty | x the location of the fixed ROI (see MAV_FRAME) | y | z | */
MAV_CMD_DO_LAST=240,/* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration | Empty | Empty | Empty | Empty | Empty | Empty | Empty | */
MAV_CMD_PREFLIGHT_CALIBRATION=241,/* Trigger calibration. This command will be only accepted if in pre-flight mode. | Gyro calibration: 0: no, 1: yes | Magnetometer calibration: 0: no, 1: yes | Ground pressure: 0: no, 1: yes | Radio calibration: 0: no, 1: yes | Empty | Empty | Empty | */
MAV_CMD_PREFLIGHT_STORAGE=245,/* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. | Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM | Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM | Reserved | Reserved | Empty | Empty | Empty | */
...
...
@@ -77,13 +78,14 @@ enum MAV_DATA_STREAM
MAV_DATA_STREAM_ENUM_END
};
/** @brief 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). */
/** @brief 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). */
enumMAV_ROI
{
MAV_ROI_WPNEXT=0,/* Point toward next waypoint. | */
MAV_ROI_WPINDEX=1,/* Point toward given waypoint. | */
MAV_ROI_LOCATION=2,/* Point toward fixed location. | */
MAV_ROI_TARGET=3,/* Point toward of given id. | */
MAV_ROI_NONE=0,/* No region of interest. | */
MAV_ROI_WPNEXT=1,/* Point toward next waypoint. | */
MAV_ROI_WPINDEX=2,/* Point toward given waypoint. | */
MAV_ROI_LOCATION=3,/* Point toward fixed location. | */
MAV_ROI_TARGET=4,/* Point toward of given id. | */
<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>
<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>
<fieldname="type"type="uint8_t">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
<fieldname="size"type="uint32_t">total data size in bytes (set on ACK only)</field>
<fieldname="packets"type="uint8_t">number of packets beeing sent (set on ACK only)</field>
<fieldname="payload"type="uint8_t">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field>
<fieldname="jpg_quality"type="uint8_t">JPEG quality out of [1,100]</field>
</message>
<messagename="ENCAPSULATED_DATA"id="171">
<fieldname="seqnr"type="uint16_t">sequence number (starting with 0 on every transmission)</field>
<fieldname="data"type="uint8_t[253]">image data bytes</field>
</message>
<messagename="BRIEF_FEATURE"id="172">
<fieldname="x"type="float">x position in m</field>
<fieldname="y"type="float">y position in m</field>
<fieldname="z"type="float">z position in m</field>
<fieldname="type"type="uint8_t">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
<fieldname="size"type="uint32_t">total data size in bytes (set on ACK only)</field>
<fieldname="packets"type="uint8_t">number of packets beeing sent (set on ACK only)</field>
<fieldname="payload"type="uint8_t">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field>
<fieldname="jpg_quality"type="uint8_t">JPEG quality out of [1,100]</field>
</message>
<messagename="ENCAPSULATED_DATA"id="171">
<fieldname="seqnr"type="uint16_t">sequence number (starting with 0 on every transmission)</field>
<fieldname="data"type="uint8_t[253]">image data bytes</field>
</message>
<messagename="BRIEF_FEATURE"id="172">
<fieldname="x"type="float">x position in m</field>
<fieldname="y"type="float">y position in m</field>
<fieldname="z"type="float">z position in m</field>
Configurable data log probes to be used inside Simulink
<fieldname="fl_1"type="float">Log value 1 </field>
<fieldname="fl_2"type="float">Log value 2 </field>
<fieldname="fl_3"type="float">Log value 3 </field>
<fieldname="fl_4"type="float">Log value 4 </field>
<fieldname="fl_5"type="float">Log value 5 </field>
<fieldname="fl_6"type="float">Log value 6 </field>
</message>
<messagename="GPS_DATE_TIME"id="179">
Pilot console PWM messges.
<fieldname="year"type="uint8_t">Year reported by Gps </field>
<fieldname="month"type="uint8_t">Month reported by Gps </field>
<fieldname="day"type="uint8_t">Day reported by Gps </field>
<fieldname="hour"type="uint8_t">Hour reported by Gps </field>
<fieldname="min"type="uint8_t">Min reported by Gps </field>
<fieldname="sec"type="uint8_t">Sec reported by Gps </field>
<fieldname="visSat"type="uint8_t">Visible sattelites reported by Gps </field>
</message>
<messagename="MID_LVL_CMDS"id="180">
Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX.
<fieldname="target"type="uint8_t">The system setting the commands</field>
<fieldname="uCommand"type="float">Log value 2 </field>
<fieldname="rCommand"type="float">Log value 3 </field>
</message>
<messagename="CTRL_SRFC_PT"id="181">
This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows:
Position Bit Code
=================================
15-8 Reserved
7 dt_pass 128
6 dla_pass 64
5 dra_pass 32
4 dr_pass 16
3 dle_pass 8
2 dre_pass 4
1 dlf_pass 2
0 drf_pass 1
Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface.
<fieldname="target"type="uint8_t">The system setting the commands</field>
<fieldname="bitfieldPt"type="uint16_t">Bitfield containing the PT configuration</field>
</message>
<messagename="SLUGS_ACTION"id="183">
Action messages focused on the SLUGS AP.
<fieldname="target"type="uint8_t">The system reporting the action</field>
<fieldname="actionId"type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field>
<fieldname="actionVal"type="uint16_t">Value associated with the action</field>
Configurable data log probes to be used inside Simulink
<fieldname="fl_1"type="float">Log value 1 </field>
<fieldname="fl_2"type="float">Log value 2 </field>
<fieldname="fl_3"type="float">Log value 3 </field>
<fieldname="fl_4"type="float">Log value 4 </field>
<fieldname="fl_5"type="float">Log value 5 </field>
<fieldname="fl_6"type="float">Log value 6 </field>
</message>
<messagename="GPS_DATE_TIME"id="179">
Pilot console PWM messges.
<fieldname="year"type="uint8_t">Year reported by Gps </field>
<fieldname="month"type="uint8_t">Month reported by Gps </field>
<fieldname="day"type="uint8_t">Day reported by Gps </field>
<fieldname="hour"type="uint8_t">Hour reported by Gps </field>
<fieldname="min"type="uint8_t">Min reported by Gps </field>
<fieldname="sec"type="uint8_t">Sec reported by Gps </field>
<fieldname="visSat"type="uint8_t">Visible sattelites reported by Gps </field>
</message>
<messagename="MID_LVL_CMDS"id="180">
Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX.
<fieldname="target"type="uint8_t">The system setting the commands</field>
<fieldname="uCommand"type="float">Log value 2 </field>
<fieldname="rCommand"type="float">Log value 3 </field>
</message>
<messagename="CTRL_SRFC_PT"id="181">
This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows:
Position Bit Code
=================================
15-8 Reserved
7 dt_pass 128
6 dla_pass 64
5 dra_pass 32
4 dr_pass 16
3 dle_pass 8
2 dre_pass 4
1 dlf_pass 2
0 drf_pass 1
Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface.
<fieldname="target"type="uint8_t">The system setting the commands</field>
<fieldname="bitfieldPt"type="uint16_t">Bitfield containing the PT configuration</field>
</message>
<messagename="SLUGS_ACTION"id="183">
Action messages focused on the SLUGS AP.
<fieldname="target"type="uint8_t">The system reporting the action</field>
<fieldname="actionId"type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field>
<fieldname="actionVal"type="uint16_t">Value associated with the action</field>
state->idle=false;///< indicates if the system is following the waypoints or is waiting
state->current_active_wp_id=-1;///< id of current waypoint
state->yaw_reached=false;///< boolean for yaw attitude reached
state->pos_reached=false;///< boolean for position reached
state->timestamp_lastoutside_orbit=0;///< timestamp when the MAV was last outside the orbit or had the wrong yaw value
state->timestamp_firstinside_orbit=0;///< timestamp when the MAV was the first time after a waypoint change inside the orbit and had the correct yaw value
if(MAVLINK_WPM_TEXT_FEEDBACK)mavlink_wpm_send_gcs_string("Broadcasted new current waypoint\n");//// printf("Broadcasted new current waypoint %u\n", wpc.seq);
}
else
{
if(MAVLINK_WPM_TEXT_FEEDBACK)mavlink_wpm_send_gcs_string("ERROR: index out of bounds\n");
}
}
/*
* @brief Directs the MAV to fly to a position
*
* Sends a message to the controller, advising it to fly to the coordinates
* of the waypoint with a given orientation
*
* @param seq The waypoint sequence number the MAV should fly to.
if(MAVLINK_WPM_TEXT_FEEDBACK)mavlink_wpm_send_gcs_string("No new setpoint set because of invalid coordinate frame of waypoint");//// if (verbose) // printf("No new set point sent to IMU because the new waypoint %u had no local coordinates\n", cur->seq);
if(MAVLINK_WPM_TEXT_FEEDBACK)mavlink_wpm_send_gcs_string("ERROR: Waypoint index out of bounds\n");//// if (verbose) // printf("ERROR: index out of bounds\n");
if(MAVLINK_WPM_TEXT_FEEDBACK)mavlink_wpm_send_gcs_string("Sent waypoint count");//// if (verbose) // printf("Sent waypoint count (%u) to ID %u\n", wpc.count, wpc.target_system);
if(MAVLINK_WPM_TEXT_FEEDBACK)mavlink_wpm_send_gcs_string("Sent waypoint");//// if (verbose) // printf("Sent waypoint %u to ID %u\n", wp->seq, wp->target_system);
if(MAVLINK_WPM_TEXT_FEEDBACK)mavlink_wpm_send_gcs_string("Sent waypoint request");//// if (verbose) // printf("Sent waypoint request %u to ID %u\n", wpr.seq, wpr.target_system);
if(verbose&&wpm.current_state==MAVLINK_WPM_STATE_IDLE)// printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST from %u changing state to MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid);
if(verbose&&wpm.current_state==MAVLINK_WPM_STATE_SENDLIST)// printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST again from %u staying in state MAVLINK_WPM_STATE_SENDLIST\n", msg->sysid);
wpm.current_state=MAVLINK_WPM_STATE_SENDLIST;
wpm.current_wp_id=0;
wpm.current_partner_sysid=msg->sysid;
wpm.current_partner_compid=msg->compid;
}
else
{
// if (verbose) // printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST from %u but have no waypoints, staying in \n", msg->sysid);
//ensure that we are in the correct state and that the first request has id 0 and the following requests have either the last id (re-send last waypoint) or last_id+1 (next waypoint)
mavlink_wpm_send_gcs_string("GOT WP REQ, state -> SEND");
#else
if(MAVLINK_WPM_VERBOSE)printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n",wpr.seq,msg->sysid);
if(MAVLINK_WPM_VERBOSE)printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n",wpr.seq,msg->sysid);
if(MAVLINK_WPM_VERBOSE)printf("Got MAVLINK_MSG_ID_WAYPOINT_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS\n",wpr.seq,msg->sysid);
mavlink_wpm_send_gcs_string("REJ. WP CMD: Req. WP was unexpected");
#else
if(MAVLINK_WPM_VERBOSE)printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).\n",wpr.seq,wpm.current_wp_id,wpm.current_wp_id+1);
#endif
}
elseif(wpr.seq>=wpm.size)
{
#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_wpm_send_gcs_string("REJ. WP CMD: Req. WP not in list");
#else
if(MAVLINK_WPM_VERBOSE)printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST because the requested waypoint ID (%u) was out of bounds.\n",wpr.seq);
if(MAVLINK_WPM_VERBOSE)printf("Ignored MAVLINK_MSG_ID_WAYPOINT_REQUEST from ID %u because i'm already talking to ID %u.\n",msg->sysid,wpm.current_partner_sysid);
#endif
}
else
{
#ifdef MAVLINK_WPM_NO_PRINTF
mavlink_wpm_send_gcs_string("REJ. WP CMD: target id mismatch");
#else
if(MAVLINK_WPM_VERBOSE)printf("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH\n");
if(verbose&&wpm.current_state==MAVLINK_WPM_STATE_GETLIST)// printf("Got MAVLINK_MSG_ID_WAYPOINT %u from %u changing state to MAVLINK_WPM_STATE_GETLIST_GETWPS\n", wp.seq, msg->sysid);
if(verbose&&wpm.current_state==MAVLINK_WPM_STATE_GETLIST_GETWPS&&wp.seq==wpm.current_wp_id)// printf("Got MAVLINK_MSG_ID_WAYPOINT %u from %u\n", wp.seq, msg->sysid);
if(verbose&&wpm.current_state==MAVLINK_WPM_STATE_GETLIST_GETWPS&&wp.seq-1==wpm.current_wp_id)// printf("Got MAVLINK_MSG_ID_WAYPOINT %u (again) from %u\n", wp.seq, msg->sysid);
// if (verbose) // printf("Ignored MAVLINK_MSG_ID_WAYPOINT %u from ID %u because i'm already talking to ID %u.\n", wp.seq, msg->sysid, wpm.current_partner_sysid);