From 1dc9785083e1ed7a7db27466fbe9f61f6bb277f7 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 22 Jan 2014 16:52:35 +0100 Subject: OFFBOARD switch added, WIP --- src/modules/commander/commander.cpp | 11 +++++++++ src/modules/sensors/sensor_params.c | 3 +-- src/modules/sensors/sensors.cpp | 29 ++++++++++------------- src/modules/uORB/topics/manual_control_setpoint.h | 4 +--- src/modules/uORB/topics/vehicle_status.h | 8 +++++++ 5 files changed, 34 insertions(+), 21 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 47053838c..e2b6ad1ca 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1410,6 +1410,17 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta } else { current_status->mission_switch = MISSION_SWITCH_MISSION; } + + /* offboard switch */ + if (!isfinite(sp_man->offboard_switch)) { + current_status->offboard_switch = OFFBOARD_SWITCH_NONE; + + } else if (sp_man->offboard_switch > STICK_ON_OFF_LIMIT) { + current_status->offboard_switch = OFFBOARD_SWITCH_OFFBOARD; + + } else { + current_status->offboard_switch = OFFBOARD_SWITCH_ONBOARD; + } } transition_result_t diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index bbc84ef93..eb771382d 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -390,8 +390,7 @@ PARAM_DEFINE_INT32(RC_MAP_MODE_SW, 5); PARAM_DEFINE_INT32(RC_MAP_RETURN_SW, 0); PARAM_DEFINE_INT32(RC_MAP_ASSIST_SW, 6); PARAM_DEFINE_INT32(RC_MAP_MISSIO_SW, 0); - -//PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0); +PARAM_DEFINE_INT32(RC_MAP_OFFB_SW, 0); PARAM_DEFINE_INT32(RC_MAP_FLAPS, 0); diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 5e8c5edbc..f87f2f282 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -246,8 +246,7 @@ private: int rc_map_return_sw; int rc_map_assisted_sw; int rc_map_mission_sw; - -// int rc_map_offboard_ctrl_mode_sw; + int rc_map_offboard_sw; int rc_map_flaps; @@ -296,8 +295,7 @@ private: param_t rc_map_return_sw; param_t rc_map_assisted_sw; param_t rc_map_mission_sw; - -// param_t rc_map_offboard_ctrl_mode_sw; + param_t rc_map_offboard_sw; param_t rc_map_flaps; @@ -515,8 +513,7 @@ Sensors::Sensors() : /* optional mode switches, not mapped per default */ _parameter_handles.rc_map_assisted_sw = param_find("RC_MAP_ASSIST_SW"); _parameter_handles.rc_map_mission_sw = param_find("RC_MAP_MISSIO_SW"); - -// _parameter_handles.rc_map_offboard_ctrl_mode_sw = param_find("RC_MAP_OFFB_SW"); + _parameter_handles.rc_map_offboard_sw = param_find("RC_MAP_OFFB_SW"); _parameter_handles.rc_map_aux1 = param_find("RC_MAP_AUX1"); _parameter_handles.rc_map_aux2 = param_find("RC_MAP_AUX2"); @@ -669,14 +666,14 @@ Sensors::parameters_update() warnx("Failed getting mission sw chan index"); } + if (param_get(_parameter_handles.rc_map_offboard_sw, &(_parameters.rc_map_offboard_sw)) != OK) { + warnx("Failed getting offboard sw chan index"); + } + if (param_get(_parameter_handles.rc_map_flaps, &(_parameters.rc_map_flaps)) != OK) { warnx("Failed getting flaps chan index"); } -// if (param_get(_parameter_handles.rc_map_offboard_ctrl_mode_sw, &(_parameters.rc_map_offboard_ctrl_mode_sw)) != OK) { -// warnx("Failed getting offboard control mode sw chan index"); -// } - param_get(_parameter_handles.rc_map_aux1, &(_parameters.rc_map_aux1)); param_get(_parameter_handles.rc_map_aux2, &(_parameters.rc_map_aux2)); param_get(_parameter_handles.rc_map_aux3, &(_parameters.rc_map_aux3)); @@ -700,11 +697,10 @@ Sensors::parameters_update() _rc.function[RETURN] = _parameters.rc_map_return_sw - 1; _rc.function[ASSISTED] = _parameters.rc_map_assisted_sw - 1; _rc.function[MISSION] = _parameters.rc_map_mission_sw - 1; + _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_sw - 1; _rc.function[FLAPS] = _parameters.rc_map_flaps - 1; -// _rc.function[OFFBOARD_MODE] = _parameters.rc_map_offboard_ctrl_mode_sw - 1; - _rc.function[AUX_1] = _parameters.rc_map_aux1 - 1; _rc.function[AUX_2] = _parameters.rc_map_aux2 - 1; _rc.function[AUX_3] = _parameters.rc_map_aux3 - 1; @@ -1289,7 +1285,7 @@ Sensors::rc_poll() manual_control.return_switch = NAN; manual_control.assisted_switch = NAN; manual_control.mission_switch = NAN; -// manual_control.auto_offboard_input_switch = NAN; + manual_control.offboard_switch = NAN; manual_control.flaps = NAN; manual_control.aux1 = NAN; @@ -1432,9 +1428,10 @@ Sensors::rc_poll() manual_control.return_switch = limit_minus_one_to_one(_rc.chan[_rc.function[RETURN]].scaled); } -// if (_rc.function[OFFBOARD_MODE] >= 0) { -// manual_control.auto_offboard_input_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled); -// } + /* offboard switch input */ + if (_rc.function[OFFBOARD_MODE] >= 0) { + manual_control.offboard_switch = limit_minus_one_to_one(_rc.chan[_rc.function[OFFBOARD_MODE]].scaled); + } /* aux functions, only assign if valid mapping is present */ if (_rc.function[AUX_1] >= 0) { diff --git a/src/modules/uORB/topics/manual_control_setpoint.h b/src/modules/uORB/topics/manual_control_setpoint.h index eac6d6e98..ab0c7a411 100644 --- a/src/modules/uORB/topics/manual_control_setpoint.h +++ b/src/modules/uORB/topics/manual_control_setpoint.h @@ -60,15 +60,13 @@ struct manual_control_setpoint_s { float return_switch; /**< land 2 position switch (mandatory): land, no effect */ float assisted_switch; /**< assisted 2 position switch (optional): seatbelt, simple */ float mission_switch; /**< mission 2 position switch (optional): mission, loiter */ + float offboard_switch; /**< offboard switch (optional): offboard, onboard */ /** * Any of the channels below may not be available and be set to NaN * to indicate that it does not contain valid data. */ - // XXX needed or parameter? - //float auto_offboard_input_switch; /**< controller setpoint source (0 = onboard, 1 = offboard) */ - float flaps; /**< flap position */ float aux1; /**< default function: camera yaw / azimuth */ diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h index 1a9dec5f5..d74b696bb 100644 --- a/src/modules/uORB/topics/vehicle_status.h +++ b/src/modules/uORB/topics/vehicle_status.h @@ -64,6 +64,7 @@ typedef enum { MAIN_STATE_SEATBELT, MAIN_STATE_EASY, MAIN_STATE_AUTO, + MAIN_STATE_OFFBOARD, } main_state_t; typedef enum { @@ -109,6 +110,12 @@ typedef enum { MISSION_SWITCH_MISSION } mission_switch_pos_t; +typedef enum { + OFFBOARD_SWITCH_NONE = 0, + OFFBOARD_SWITCH_OFFBOARD, + OFFBOARD_SWITCH_ONBOARD +} offboard_switch_pos_t; + enum VEHICLE_MODE_FLAG { VEHICLE_MODE_FLAG_SAFETY_ARMED = 128, VEHICLE_MODE_FLAG_MANUAL_INPUT_ENABLED = 64, @@ -184,6 +191,7 @@ struct vehicle_status_s return_switch_pos_t return_switch; assisted_switch_pos_t assisted_switch; mission_switch_pos_t mission_switch; + offboard_switch_pos_t offboard_switch; bool condition_battery_voltage_valid; bool condition_system_in_air_restore; /**< true if we can restore in mid air */ -- cgit v1.2.3 From 37e28e7fa82a965967abba6650ba24a31aba10d3 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 22 Jan 2014 17:04:07 +0100 Subject: commander: OFFBOARD mode added, WIP --- src/modules/commander/commander.cpp | 80 ++++++++++++++------------ src/modules/commander/state_machine_helper.cpp | 6 ++ 2 files changed, 49 insertions(+), 37 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index e2b6ad1ca..dfcb1cc9f 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1429,56 +1429,62 @@ check_main_state_machine(struct vehicle_status_s *current_status) /* evaluate the main state machine */ transition_result_t res = TRANSITION_DENIED; - switch (current_status->mode_switch) { - case MODE_SWITCH_MANUAL: - res = main_state_transition(current_status, MAIN_STATE_MANUAL); - // TRANSITION_DENIED is not possible here - break; + if (current_status->offboard_switch == OFFBOARD_SWITCH_OFFBOARD) { + /* offboard switch overrides main switch */ + res = main_state_transition(current_status, MAIN_STATE_OFFBOARD); - case MODE_SWITCH_ASSISTED: - if (current_status->assisted_switch == ASSISTED_SWITCH_EASY) { - res = main_state_transition(current_status, MAIN_STATE_EASY); + } else { + switch (current_status->mode_switch) { + case MODE_SWITCH_MANUAL: + res = main_state_transition(current_status, MAIN_STATE_MANUAL); + // TRANSITION_DENIED is not possible here + break; - if (res != TRANSITION_DENIED) - break; // changed successfully or already in this state + case MODE_SWITCH_ASSISTED: + if (current_status->assisted_switch == ASSISTED_SWITCH_EASY) { + res = main_state_transition(current_status, MAIN_STATE_EASY); - // else fallback to SEATBELT - print_reject_mode("EASY"); - } + if (res != TRANSITION_DENIED) + break; // changed successfully or already in this state - res = main_state_transition(current_status, MAIN_STATE_SEATBELT); + // else fallback to SEATBELT + print_reject_mode("EASY"); + } - if (res != TRANSITION_DENIED) - break; // changed successfully or already in this mode + res = main_state_transition(current_status, MAIN_STATE_SEATBELT); - if (current_status->assisted_switch != ASSISTED_SWITCH_EASY) // don't print both messages - print_reject_mode("SEATBELT"); + if (res != TRANSITION_DENIED) + break; // changed successfully or already in this mode - // else fallback to MANUAL - res = main_state_transition(current_status, MAIN_STATE_MANUAL); - // TRANSITION_DENIED is not possible here - break; + if (current_status->assisted_switch != ASSISTED_SWITCH_EASY) // don't print both messages + print_reject_mode("SEATBELT"); + + // else fallback to MANUAL + res = main_state_transition(current_status, MAIN_STATE_MANUAL); + // TRANSITION_DENIED is not possible here + break; - case MODE_SWITCH_AUTO: - res = main_state_transition(current_status, MAIN_STATE_AUTO); + case MODE_SWITCH_AUTO: + res = main_state_transition(current_status, MAIN_STATE_AUTO); - if (res != TRANSITION_DENIED) - break; // changed successfully or already in this state + if (res != TRANSITION_DENIED) + break; // changed successfully or already in this state - // else fallback to SEATBELT (EASY likely will not work too) - print_reject_mode("AUTO"); - res = main_state_transition(current_status, MAIN_STATE_SEATBELT); + // else fallback to SEATBELT (EASY likely will not work too) + print_reject_mode("AUTO"); + res = main_state_transition(current_status, MAIN_STATE_SEATBELT); - if (res != TRANSITION_DENIED) - break; // changed successfully or already in this state + if (res != TRANSITION_DENIED) + break; // changed successfully or already in this state - // else fallback to MANUAL - res = main_state_transition(current_status, MAIN_STATE_MANUAL); - // TRANSITION_DENIED is not possible here - break; + // else fallback to MANUAL + res = main_state_transition(current_status, MAIN_STATE_MANUAL); + // TRANSITION_DENIED is not possible here + break; - default: - break; + default: + break; + } } return res; diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 731e0e3ff..e5599e1c3 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -262,6 +262,12 @@ main_state_transition(struct vehicle_status_s *current_state, main_state_t new_m ret = TRANSITION_CHANGED; } + break; + + case MAIN_STATE_OFFBOARD: + + ret = TRANSITION_CHANGED; + break; } -- cgit v1.2.3 From f069fe9f61d24b5a6cc66d60afd3f8b5e568824a Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 22 Jan 2014 19:25:14 +0100 Subject: OFFBOARD mode support in commander, mavlink, mc_att_control, WIP --- src/modules/commander/commander.cpp | 66 +++++++++------ src/modules/commander/px4_custom_mode.h | 1 + src/modules/mavlink/mavlink.c | 2 + src/modules/mc_att_control/mc_att_control_main.cpp | 99 ++++++++++++---------- src/modules/navigator/navigator_main.cpp | 16 +++- 5 files changed, 110 insertions(+), 74 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index dfcb1cc9f..7b69f2b76 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -411,42 +411,52 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe /* set main state */ transition_result_t main_res = TRANSITION_DENIED; - if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) { - /* use autopilot-specific mode */ - if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) { - /* MANUAL */ - main_res = main_state_transition(status, MAIN_STATE_MANUAL); - - } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) { - /* SEATBELT */ - main_res = main_state_transition(status, MAIN_STATE_SEATBELT); - - } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) { - /* EASY */ - main_res = main_state_transition(status, MAIN_STATE_EASY); - - } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) { - /* AUTO */ - main_res = main_state_transition(status, MAIN_STATE_AUTO); - } + if (status->rc_signal_lost) { + /* allow mode switching by command only if no RC signal */ + if (base_mode & MAV_MODE_FLAG_CUSTOM_MODE_ENABLED) { + /* use autopilot-specific mode */ + if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) { + /* MANUAL */ + main_res = main_state_transition(status, MAIN_STATE_MANUAL); - } else { - /* use base mode */ - if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) { - /* AUTO */ - main_res = main_state_transition(status, MAIN_STATE_AUTO); + } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_SEATBELT) { + /* SEATBELT */ + main_res = main_state_transition(status, MAIN_STATE_SEATBELT); - } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) { - if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) { + } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_EASY) { /* EASY */ main_res = main_state_transition(status, MAIN_STATE_EASY); - } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) { - /* MANUAL */ - main_res = main_state_transition(status, MAIN_STATE_MANUAL); + } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) { + /* AUTO */ + main_res = main_state_transition(status, MAIN_STATE_AUTO); + + } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD) { + /* OFFBOARD */ + main_res = main_state_transition(status, MAIN_STATE_OFFBOARD); + } + + } else { + /* use base mode */ + if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) { + /* AUTO */ + main_res = main_state_transition(status, MAIN_STATE_AUTO); + + } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) { + if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) { + /* EASY */ + main_res = main_state_transition(status, MAIN_STATE_EASY); + + } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) { + /* MANUAL */ + main_res = main_state_transition(status, MAIN_STATE_MANUAL); + } } } + } else { + mavlink_log_info(mavlink_fd, "RC signal is valid, ignoring set mode cmd"); } + if (main_res == TRANSITION_CHANGED) ret = true; diff --git a/src/modules/commander/px4_custom_mode.h b/src/modules/commander/px4_custom_mode.h index b60a7e0b9..4843e72c3 100644 --- a/src/modules/commander/px4_custom_mode.h +++ b/src/modules/commander/px4_custom_mode.h @@ -13,6 +13,7 @@ enum PX4_CUSTOM_MAIN_MODE { PX4_CUSTOM_MAIN_MODE_SEATBELT, PX4_CUSTOM_MAIN_MODE_EASY, PX4_CUSTOM_MAIN_MODE_AUTO, + PX4_CUSTOM_MAIN_MODE_OFFBOARD, }; enum PX4_CUSTOM_SUB_MODE_AUTO { diff --git a/src/modules/mavlink/mavlink.c b/src/modules/mavlink/mavlink.c index 4f8091716..70229558c 100644 --- a/src/modules/mavlink/mavlink.c +++ b/src/modules/mavlink/mavlink.c @@ -231,6 +231,8 @@ get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_base_mode, u } else if (control_mode.nav_state == NAV_STATE_RTL) { custom_mode.sub_mode = PX4_CUSTOM_SUB_MODE_AUTO_RTL; } + } else if (v_status.main_state == MAIN_STATE_OFFBOARD) { + custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_OFFBOARD; } *mavlink_custom_mode = custom_mode.data; diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 245ac024b..c4c6c0138 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -480,64 +480,73 @@ MulticopterAttitudeControl::task_main() float yaw_sp_move_rate = 0.0f; bool publish_att_sp = false; - /* define which input is the dominating control input */ - if (_control_mode.flag_control_manual_enabled) { - /* manual input */ - if (!_control_mode.flag_control_climb_rate_enabled) { - /* pass throttle directly if not in altitude control mode */ - _att_sp.thrust = _manual.throttle; - } + if (_control_mode.flag_control_offboard_enabled) { + /* offboard control */ + // TODO set _att_sp or _rates_sp here depending on offboard control mode + // TODO _control_mode.flag_control_XXX flags are all false, set it according to ofboard control mode + // but it's not very beautiful, need to think how to do it better - if (!_arming.armed) { - /* reset yaw setpoint when disarmed */ - reset_yaw_sp = true; - } + } else { + /* onboard control */ + /* define which input is the dominating control input */ + if (_control_mode.flag_control_manual_enabled) { + /* manual input */ + if (!_control_mode.flag_control_climb_rate_enabled) { + /* pass throttle directly if not in altitude control mode */ + _att_sp.thrust = _manual.throttle; + } - if (_control_mode.flag_control_attitude_enabled) { - /* control attitude, update attitude setpoint depending on mode */ + if (!_arming.armed) { + /* reset yaw setpoint when disarmed */ + reset_yaw_sp = true; + } - if (_att_sp.thrust < 0.1f) { - // TODO - //if (_status.condition_landed) { - /* reset yaw setpoint if on ground */ - // reset_yaw_sp = true; - //} - } else { - if (_manual.yaw < -YAW_DEADZONE || YAW_DEADZONE < _manual.yaw) { - /* move yaw setpoint */ - yaw_sp_move_rate = _manual.yaw; - _att_sp.yaw_body = _wrap_pi(_att_sp.yaw_body + yaw_sp_move_rate * dt); + if (_control_mode.flag_control_attitude_enabled) { + /* control attitude, update attitude setpoint depending on mode */ + + if (_att_sp.thrust < 0.1f) { + // TODO + //if (_status.condition_landed) { + /* reset yaw setpoint if on ground */ + // reset_yaw_sp = true; + //} + } else { + if (_manual.yaw < -YAW_DEADZONE || YAW_DEADZONE < _manual.yaw) { + /* move yaw setpoint */ + yaw_sp_move_rate = _manual.yaw; + _att_sp.yaw_body = _wrap_pi(_att_sp.yaw_body + yaw_sp_move_rate * dt); + _att_sp.R_valid = false; + publish_att_sp = true; + } + } + + /* reset yaw setpint to current position if needed */ + if (reset_yaw_sp) { + reset_yaw_sp = false; + _att_sp.yaw_body = _att.yaw; _att_sp.R_valid = false; publish_att_sp = true; } - } - /* reset yaw setpint to current position if needed */ - if (reset_yaw_sp) { - reset_yaw_sp = false; - _att_sp.yaw_body = _att.yaw; - _att_sp.R_valid = false; - publish_att_sp = true; - } + if (!_control_mode.flag_control_velocity_enabled) { + /* update attitude setpoint if not in position control mode */ + _att_sp.roll_body = _manual.roll; + _att_sp.pitch_body = _manual.pitch; + _att_sp.R_valid = false; + publish_att_sp = true; + } - if (!_control_mode.flag_control_velocity_enabled) { - /* update attitude setpoint if not in position control mode */ - _att_sp.roll_body = _manual.roll; - _att_sp.pitch_body = _manual.pitch; - _att_sp.R_valid = false; - publish_att_sp = true; + } else { + /* manual rate inputs (ACRO) */ + // TODO + /* reset yaw setpoint after ACRO */ + reset_yaw_sp = true; } } else { - /* manual rate inputs (ACRO) */ - // TODO - /* reset yaw setpoint after ACRO */ + /* reset yaw setpoint after non-manual control */ reset_yaw_sp = true; } - - } else { - /* reset yaw setpoint after non-manual control */ - reset_yaw_sp = true; } if (_att_sp.R_valid) { diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index ca5735509..7285e243e 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1463,11 +1463,11 @@ Navigator::publish_control_mode() _control_mode.flag_external_manual_override_ok = !_vstatus.is_rotary_wing; _control_mode.flag_system_hil_enabled = _vstatus.hil_state == HIL_STATE_ON; - _control_mode.flag_control_offboard_enabled = false; _control_mode.flag_control_flighttermination_enabled = false; switch (_vstatus.main_state) { case MAIN_STATE_MANUAL: + _control_mode.flag_control_offboard_enabled = false; _control_mode.flag_control_manual_enabled = true; _control_mode.flag_control_rates_enabled = _vstatus.is_rotary_wing; _control_mode.flag_control_attitude_enabled = _vstatus.is_rotary_wing; @@ -1478,6 +1478,7 @@ Navigator::publish_control_mode() break; case MAIN_STATE_SEATBELT: + _control_mode.flag_control_offboard_enabled = false; _control_mode.flag_control_manual_enabled = true; _control_mode.flag_control_rates_enabled = true; _control_mode.flag_control_attitude_enabled = true; @@ -1488,6 +1489,7 @@ Navigator::publish_control_mode() break; case MAIN_STATE_EASY: + _control_mode.flag_control_offboard_enabled = false; _control_mode.flag_control_manual_enabled = true; _control_mode.flag_control_rates_enabled = true; _control_mode.flag_control_attitude_enabled = true; @@ -1498,6 +1500,7 @@ Navigator::publish_control_mode() break; case MAIN_STATE_AUTO: + _control_mode.flag_control_offboard_enabled = false; _control_mode.flag_control_manual_enabled = false; if (myState == NAV_STATE_READY) { /* disable all controllers, armed but idle */ @@ -1517,6 +1520,17 @@ Navigator::publish_control_mode() } break; + case MAIN_STATE_OFFBOARD: + _control_mode.flag_control_offboard_enabled = true; + _control_mode.flag_control_manual_enabled = false; + _control_mode.flag_control_rates_enabled = false; + _control_mode.flag_control_attitude_enabled = false; + _control_mode.flag_control_altitude_enabled = false; + _control_mode.flag_control_climb_rate_enabled = false; + _control_mode.flag_control_position_enabled = false; + _control_mode.flag_control_velocity_enabled = false; + break; + default: break; } -- cgit v1.2.3 From 6bb85a323ce7f152aead0c9133d86e5e900bd7ba Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Thu, 23 Jan 2014 11:01:22 +0000 Subject: added offboard data handling in mc_att_control_main.cpp --- src/modules/mc_att_control/mc_att_control_main.cpp | 67 +++++++++++++++++++++- 1 file changed, 64 insertions(+), 3 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index c4c6c0138..129e5df8f 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -63,6 +63,7 @@ #include #include #include +#include #include #include #include @@ -118,6 +119,7 @@ private: int _control_mode_sub; /**< vehicle control mode subscription */ int _params_sub; /**< notification of parameter updates */ int _manual_sub; /**< notification of manual control updates */ + int _offboard_sub; /**< notification of offboard control updates */ int _arming_sub; /**< arming status of outputs */ orb_advert_t _att_sp_pub; /**< attitude setpoint publication */ @@ -127,6 +129,7 @@ private: struct vehicle_attitude_s _att; /**< vehicle attitude */ struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */ struct manual_control_setpoint_s _manual; /**< r/c channel data */ + struct offboard_control_setpoint_s _offboard; /**< offboard data */ struct vehicle_control_mode_s _control_mode; /**< vehicle control mode */ struct actuator_controls_s _actuators; /**< actuator control inputs */ struct actuator_armed_s _arming; /**< actuator arming status */ @@ -173,6 +176,11 @@ private: * Check for changes in manual inputs. */ void vehicle_manual_poll(); + + /** + * Check for changes in offboard inputs. + */ + void vehicle_offboard_poll(); /** * Check for set triplet updates. @@ -339,6 +347,23 @@ MulticopterAttitudeControl::vehicle_manual_poll() } } +void +MulticopterAttitudeControl::vehicle_offboard_poll() +{ + bool offboard_updated; + + /* get offboard inputs */ + orb_check(_offboard_sub, &offboard_updated); + + if (offboard_updated) { + + orb_copy(ORB_ID(offboard_control_setpoint), _offboard_sub, &_offboard); + } + +} + + + void MulticopterAttitudeControl::vehicle_setpoint_poll() { @@ -363,6 +388,8 @@ MulticopterAttitudeControl::arming_status_poll() } } + + void MulticopterAttitudeControl::task_main_trampoline(int argc, char *argv[]) { @@ -476,15 +503,49 @@ MulticopterAttitudeControl::task_main() vehicle_control_mode_poll(); arming_status_poll(); vehicle_manual_poll(); + vehicle_offboard_poll(); float yaw_sp_move_rate = 0.0f; bool publish_att_sp = false; if (_control_mode.flag_control_offboard_enabled) { - /* offboard control */ - // TODO set _att_sp or _rates_sp here depending on offboard control mode + /* offboard control */ + // TODO set _att_sp or _rates_sp here depending on offboard control mode // TODO _control_mode.flag_control_XXX flags are all false, set it according to ofboard control mode // but it's not very beautiful, need to think how to do it better + + // If control mode is rates set _rates_sp + if(_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) { + _rates_sp.roll = _offboard.p1; + _rates_sp.pitch = _offboard.p2; + _rates_sp.yaw = _offboard.p3; + _rates_sp.roll = _offboard.p4; + + // If control mode is atitude set _att_sp + } else if (_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) { + _control_mode.flag_control_attitude_enabled = true; + + + /* pass throttle directly if not in altitude control mode */ + if (!_control_mode.flag_control_climb_rate_enabled) { + _att_sp.thrust = _offboard.p4; + } + + if (!_arming.armed) { + /* reset yaw setpoint when disarmed */ + _att_sp.yaw_body = _att.yaw; + } + else{ + _att_sp.yaw_body = _offboard.p3; + } + + _att_sp.roll_body = _offboard.p1; + _att_sp.pitch_body = _offboard.p2; + + _att_sp.R_valid = false; + publish_att_sp = true; + } + } else { /* onboard control */ @@ -565,7 +626,7 @@ MulticopterAttitudeControl::task_main() if (publish_att_sp) { /* publish the attitude setpoint */ _att_sp.timestamp = hrt_absolute_time(); - +printf("att_sp RPYT: %.2f %.2f %.2f %.2f", _att_sp.roll_body, _att_sp.pitch_body, _att_sp.yaw_body, _att_sp.thrust) if (_att_sp_pub > 0) { orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_att_sp); -- cgit v1.2.3 From d4ae1c01adea93f23b71e742346b2d892204716c Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 23 Jan 2014 12:24:04 +0100 Subject: Revert "added offboard data handling in mc_att_control_main.cpp" This reverts commit 6bb85a323ce7f152aead0c9133d86e5e900bd7ba. --- src/modules/mc_att_control/mc_att_control_main.cpp | 67 +--------------------- 1 file changed, 3 insertions(+), 64 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 129e5df8f..c4c6c0138 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -63,7 +63,6 @@ #include #include #include -#include #include #include #include @@ -119,7 +118,6 @@ private: int _control_mode_sub; /**< vehicle control mode subscription */ int _params_sub; /**< notification of parameter updates */ int _manual_sub; /**< notification of manual control updates */ - int _offboard_sub; /**< notification of offboard control updates */ int _arming_sub; /**< arming status of outputs */ orb_advert_t _att_sp_pub; /**< attitude setpoint publication */ @@ -129,7 +127,6 @@ private: struct vehicle_attitude_s _att; /**< vehicle attitude */ struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */ struct manual_control_setpoint_s _manual; /**< r/c channel data */ - struct offboard_control_setpoint_s _offboard; /**< offboard data */ struct vehicle_control_mode_s _control_mode; /**< vehicle control mode */ struct actuator_controls_s _actuators; /**< actuator control inputs */ struct actuator_armed_s _arming; /**< actuator arming status */ @@ -176,11 +173,6 @@ private: * Check for changes in manual inputs. */ void vehicle_manual_poll(); - - /** - * Check for changes in offboard inputs. - */ - void vehicle_offboard_poll(); /** * Check for set triplet updates. @@ -347,23 +339,6 @@ MulticopterAttitudeControl::vehicle_manual_poll() } } -void -MulticopterAttitudeControl::vehicle_offboard_poll() -{ - bool offboard_updated; - - /* get offboard inputs */ - orb_check(_offboard_sub, &offboard_updated); - - if (offboard_updated) { - - orb_copy(ORB_ID(offboard_control_setpoint), _offboard_sub, &_offboard); - } - -} - - - void MulticopterAttitudeControl::vehicle_setpoint_poll() { @@ -388,8 +363,6 @@ MulticopterAttitudeControl::arming_status_poll() } } - - void MulticopterAttitudeControl::task_main_trampoline(int argc, char *argv[]) { @@ -503,49 +476,15 @@ MulticopterAttitudeControl::task_main() vehicle_control_mode_poll(); arming_status_poll(); vehicle_manual_poll(); - vehicle_offboard_poll(); float yaw_sp_move_rate = 0.0f; bool publish_att_sp = false; if (_control_mode.flag_control_offboard_enabled) { - /* offboard control */ - // TODO set _att_sp or _rates_sp here depending on offboard control mode + /* offboard control */ + // TODO set _att_sp or _rates_sp here depending on offboard control mode // TODO _control_mode.flag_control_XXX flags are all false, set it according to ofboard control mode // but it's not very beautiful, need to think how to do it better - - // If control mode is rates set _rates_sp - if(_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES) { - _rates_sp.roll = _offboard.p1; - _rates_sp.pitch = _offboard.p2; - _rates_sp.yaw = _offboard.p3; - _rates_sp.roll = _offboard.p4; - - // If control mode is atitude set _att_sp - } else if (_offboard.mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) { - _control_mode.flag_control_attitude_enabled = true; - - - /* pass throttle directly if not in altitude control mode */ - if (!_control_mode.flag_control_climb_rate_enabled) { - _att_sp.thrust = _offboard.p4; - } - - if (!_arming.armed) { - /* reset yaw setpoint when disarmed */ - _att_sp.yaw_body = _att.yaw; - } - else{ - _att_sp.yaw_body = _offboard.p3; - } - - _att_sp.roll_body = _offboard.p1; - _att_sp.pitch_body = _offboard.p2; - - _att_sp.R_valid = false; - publish_att_sp = true; - } - } else { /* onboard control */ @@ -626,7 +565,7 @@ MulticopterAttitudeControl::task_main() if (publish_att_sp) { /* publish the attitude setpoint */ _att_sp.timestamp = hrt_absolute_time(); -printf("att_sp RPYT: %.2f %.2f %.2f %.2f", _att_sp.roll_body, _att_sp.pitch_body, _att_sp.yaw_body, _att_sp.thrust) + if (_att_sp_pub > 0) { orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_att_sp); -- cgit v1.2.3 From 0877fcba0312cf859b2a8ccd9eb3b6d56ecaf7e4 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 23 Jan 2014 17:52:02 +0100 Subject: offboard setpoint support --- src/modules/commander/commander.cpp | 213 ++++++++++++++++++------------- src/modules/mavlink/mavlink_receiver.cpp | 48 +++++-- src/modules/navigator/navigator_main.cpp | 57 ++++++++- 3 files changed, 215 insertions(+), 103 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 7b69f2b76..fa815bdfe 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -119,6 +119,7 @@ extern struct system_load_s system_load; #define POSITION_TIMEOUT 1000000 /**< consider the local or global position estimate invalid after 1s */ #define RC_TIMEOUT 100000 +#define OFFBOARD_TIMEOUT 200000 #define DIFFPRESS_TIMEOUT 2000000 #define PRINT_INTERVAL 5000000 @@ -699,9 +700,9 @@ int commander_thread_main(int argc, char *argv[]) memset(&sp_man, 0, sizeof(sp_man)); /* Subscribe to offboard control data */ - int sp_offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); - struct offboard_control_setpoint_s sp_offboard; - memset(&sp_offboard, 0, sizeof(sp_offboard)); + int offboard_sp_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); + struct offboard_control_setpoint_s offboard_sp; + memset(&offboard_sp, 0, sizeof(offboard_sp)); /* Subscribe to global position */ int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position)); @@ -815,10 +816,10 @@ int commander_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(manual_control_setpoint), sp_man_sub, &sp_man); } - orb_check(sp_offboard_sub, &updated); + orb_check(offboard_sp_sub, &updated); if (updated) { - orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard); + orb_copy(ORB_ID(offboard_control_setpoint), offboard_sp_sub, &offboard_sp); } orb_check(sensor_sub, &updated); @@ -1040,124 +1041,162 @@ int commander_thread_main(int argc, char *argv[]) } } - /* ignore RC signals if in offboard control mode */ - if (!status.offboard_control_signal_found_once && sp_man.timestamp != 0) { - /* start RC input check */ - if (hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) { - /* handle the case where RC signal was regained */ - if (!status.rc_signal_found_once) { - status.rc_signal_found_once = true; - mavlink_log_critical(mavlink_fd, "#audio: detected RC signal first time"); - status_changed = true; + /* start RC input check */ + if (hrt_absolute_time() < sp_man.timestamp + RC_TIMEOUT) { + /* handle the case where RC signal was regained */ + if (!status.rc_signal_found_once) { + status.rc_signal_found_once = true; + mavlink_log_critical(mavlink_fd, "#audio: detected RC signal first time"); + status_changed = true; - } else { - if (status.rc_signal_lost) { - mavlink_log_critical(mavlink_fd, "#audio: RC signal regained"); - status_changed = true; - } + } else { + if (status.rc_signal_lost) { + mavlink_log_critical(mavlink_fd, "#audio: RC signal regained"); + status_changed = true; } + } - status.rc_signal_lost = false; - - transition_result_t res; // store all transitions results here + status.rc_signal_lost = false; - /* arm/disarm by RC */ - res = TRANSITION_NOT_CHANGED; + transition_result_t res; // store all transitions results here - /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSISTED mode and landed) -> disarm - * do it only for rotary wings */ - if (status.is_rotary_wing && - (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) && - (status.main_state == MAIN_STATE_MANUAL || status.condition_landed) && - sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { + /* arm/disarm by RC */ + res = TRANSITION_NOT_CHANGED; - if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) { - /* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */ - arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); - res = arming_state_transition(&status, &safety, new_arming_state, &armed); - stick_off_counter = 0; + /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSISTED mode and landed) -> disarm + * do it only for rotary wings */ + if (status.is_rotary_wing && + (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) && + (status.main_state == MAIN_STATE_MANUAL || status.condition_landed) && + sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { - } else { - stick_off_counter++; - } + if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) { + /* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */ + arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); + res = arming_state_transition(&status, &safety, new_arming_state, &armed); + stick_off_counter = 0; } else { - stick_off_counter = 0; + stick_off_counter++; } - /* check if left stick is in lower right position and we're in MANUAL mode -> arm */ - if (status.arming_state == ARMING_STATE_STANDBY && - sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { - if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) { - if (safety.safety_switch_available && !safety.safety_off) { - print_reject_arm("NOT ARMING: Press safety switch first."); - - } else if (status.main_state != MAIN_STATE_MANUAL) { - print_reject_arm("NOT ARMING: Switch to MANUAL mode first."); + } else { + stick_off_counter = 0; + } - } else { - res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed); - } + /* check if left stick is in lower right position and we're in MANUAL mode -> arm */ + if (status.arming_state == ARMING_STATE_STANDBY && + sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { + if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) { + if (safety.safety_switch_available && !safety.safety_off) { + print_reject_arm("NOT ARMING: Press safety switch first."); - stick_on_counter = 0; + } else if (status.main_state != MAIN_STATE_MANUAL) { + print_reject_arm("NOT ARMING: Switch to MANUAL mode first."); } else { - stick_on_counter++; + res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed); } - } else { stick_on_counter = 0; + + } else { + stick_on_counter++; } - if (res == TRANSITION_CHANGED) { - if (status.arming_state == ARMING_STATE_ARMED) { - mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC"); + } else { + stick_on_counter = 0; + } - } else { - mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC"); - } + if (res == TRANSITION_CHANGED) { + if (status.arming_state == ARMING_STATE_ARMED) { + mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC"); - } else if (res == TRANSITION_DENIED) { - warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); - mavlink_log_critical(mavlink_fd, "#audio: ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); + } else { + mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC"); } - /* fill current_status according to mode switches */ - check_mode_switches(&sp_man, &status); + } else if (res == TRANSITION_DENIED) { + warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); + mavlink_log_critical(mavlink_fd, "#audio: ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); + } + + /* fill current_status according to mode switches */ + check_mode_switches(&sp_man, &status); - /* evaluate the main state machine */ - res = check_main_state_machine(&status); + /* evaluate the main state machine */ + res = check_main_state_machine(&status); - if (res == TRANSITION_CHANGED) { - //mavlink_log_info(mavlink_fd, "[cmd] main state: %d", status.main_state); - tune_positive(); + if (res == TRANSITION_CHANGED) { + //mavlink_log_info(mavlink_fd, "[cmd] main state: %d", status.main_state); + tune_positive(); - } else if (res == TRANSITION_DENIED) { - /* DENIED here indicates bug in the commander */ - warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); - mavlink_log_critical(mavlink_fd, "#audio: ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); + } else if (res == TRANSITION_DENIED) { + /* DENIED here indicates bug in the commander */ + warnx("ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); + mavlink_log_critical(mavlink_fd, "#audio: ERROR: main denied: arm %d main %d mode_sw %d", status.arming_state, status.main_state, status.mode_switch); + } + + } else { + if (!status.rc_signal_lost) { + mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: RC SIGNAL LOST"); + status.rc_signal_lost = true; + status_changed = true; + } + if (status.main_state != MAIN_STATE_AUTO && armed.armed) { + transition_result_t res = main_state_transition(&status, MAIN_STATE_AUTO); + if (res == TRANSITION_CHANGED) { + mavlink_log_critical(mavlink_fd, "#audio: failsafe, switching to RTL mode"); + status.set_nav_state = NAV_STATE_RTL; + status.set_nav_state_timestamp = hrt_absolute_time(); + } else if (status.main_state != MAIN_STATE_SEATBELT) { + res = main_state_transition(&status, MAIN_STATE_SEATBELT); + if (res == TRANSITION_CHANGED) { + mavlink_log_critical(mavlink_fd, "#audio: failsafe, switching to SEATBELT mode"); + } } + } + } + + /* check offboard signal */ + if (hrt_absolute_time() < offboard_sp.timestamp + OFFBOARD_TIMEOUT) { + if (!status.offboard_control_signal_found_once) { + status.offboard_control_signal_found_once = true; + mavlink_log_info(mavlink_fd, "[cmd] detected offboard signal first time"); + status_changed = true; } else { - if (!status.rc_signal_lost) { - mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: RC SIGNAL LOST"); - status.rc_signal_lost = true; + if (status.offboard_control_signal_lost) { + mavlink_log_info(mavlink_fd, "[cmd] offboard signal regained"); status_changed = true; } - if (status.main_state != MAIN_STATE_AUTO && armed.armed) { - transition_result_t res = main_state_transition(&status, MAIN_STATE_AUTO); - if (res == TRANSITION_CHANGED) { - mavlink_log_critical(mavlink_fd, "#audio: failsafe, switching to RTL mode"); - status.set_nav_state = NAV_STATE_RTL; - status.set_nav_state_timestamp = hrt_absolute_time(); - } else if (status.main_state != MAIN_STATE_SEATBELT) { - res = main_state_transition(&status, MAIN_STATE_SEATBELT); + } + + status.offboard_control_signal_lost = false; + + if (status.main_state == MAIN_STATE_OFFBOARD) { + if (offboard_sp.armed && !armed.armed) { + if (!safety.safety_switch_available || safety.safety_off) { + transition_result_t res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed); if (res == TRANSITION_CHANGED) { - mavlink_log_critical(mavlink_fd, "#audio: failsafe, switching to SEATBELT mode"); + mavlink_log_info(mavlink_fd, "[cmd] ARMED by offboard signal"); } } + } else if (!offboard_sp.armed && armed.armed) { + arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); + transition_result_t res = arming_state_transition(&status, &safety, new_arming_state, &armed); + if (res == TRANSITION_CHANGED) { + mavlink_log_info(mavlink_fd, "[cmd] DISARMED by offboard signal"); + } } } + + } else { + if (!status.offboard_control_signal_lost) { + mavlink_log_critical(mavlink_fd, "[cmd[ CRITICAL: OFFBOARD SIGNAL LOST"); + status.offboard_control_signal_lost = true; + status_changed = true; + } } /* Flight termination in manual mode if assisted switch is on easy position //xxx hack! */ @@ -1264,7 +1303,7 @@ int commander_thread_main(int argc, char *argv[]) led_deinit(); buzzer_deinit(); close(sp_man_sub); - close(sp_offboard_sub); + close(offboard_sp_sub); close(local_position_sub); close(global_position_sub); close(gps_sub); diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 4f9c718d2..62597d91a 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -97,6 +97,7 @@ static mavlink_status_t status; static struct vehicle_vicon_position_s vicon_position; static struct vehicle_command_s vcmd; static struct offboard_control_setpoint_s offboard_control_sp; +static struct vehicle_attitude_setpoint_s att_sp; struct vehicle_global_position_s hil_global_pos; struct vehicle_local_position_s hil_local_pos; @@ -125,6 +126,7 @@ static orb_advert_t cmd_pub = -1; static orb_advert_t flow_pub = -1; static orb_advert_t offboard_control_sp_pub = -1; +static orb_advert_t att_sp_pub = -1; static orb_advert_t vicon_position_pub = -1; static orb_advert_t telemetry_status_pub = -1; @@ -266,8 +268,8 @@ handle_message(mavlink_message_t *msg) /* Handle quadrotor motor setpoints */ if (msg->msgid == MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST) { - mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint; - mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint); + mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_swarm_setpoint; + mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_swarm_setpoint); if (mavlink_system.sysid < 4) { @@ -281,7 +283,7 @@ handle_message(mavlink_message_t *msg) uint8_t ml_mode = 0; bool ml_armed = false; - switch (quad_motors_setpoint.mode) { + switch (quad_swarm_setpoint.mode) { case 0: ml_armed = false; break; @@ -307,12 +309,12 @@ handle_message(mavlink_message_t *msg) break; } - offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX; - offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX; - offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX; - offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX; + offboard_control_sp.p1 = (float)quad_swarm_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX; + offboard_control_sp.p2 = (float)quad_swarm_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX; + offboard_control_sp.p3 = (float)quad_swarm_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX; + offboard_control_sp.p4 = (float)quad_swarm_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX; - if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) { + if (quad_swarm_setpoint.thrust[mavlink_system.sysid - 1] == 0) { ml_armed = false; } @@ -326,9 +328,37 @@ handle_message(mavlink_message_t *msg) offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp); } else { - /* Publish */ + /* publish */ orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp); } + + if (v_status.main_state == MAIN_STATE_OFFBOARD) { + /* in offboard mode also publish setpoint directly */ + switch (offboard_control_sp.mode) { + case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: + att_sp.timestamp = hrt_absolute_time(); + att_sp.roll_body = offboard_control_sp.p1; + att_sp.pitch_body = offboard_control_sp.p2; + att_sp.yaw_body = offboard_control_sp.p3; + att_sp.thrust = offboard_control_sp.p4; + att_sp.R_valid = false; + att_sp.q_d_valid = false; + att_sp.q_e_valid = false; + att_sp.roll_reset_integral = false; + + /* check if topic has to be advertised */ + if (att_sp_pub <= 0) { + att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); + + } else { + /* publish */ + orb_publish(ORB_ID(vehicle_attitude_setpoint), att_sp_pub, &att_sp); + } + break; + default: + break; + } + } } } diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 7285e243e..f77c48207 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -72,6 +72,7 @@ #include #include #include +#include #include #include #include @@ -149,8 +150,9 @@ private: int _vstatus_sub; /**< vehicle status subscription */ int _params_sub; /**< notification of parameter updates */ int _offboard_mission_sub; /**< notification of offboard mission updates */ - int _onboard_mission_sub; /**< notification of onboard mission updates */ + int _onboard_mission_sub; /**< notification of onboard mission updates */ int _capabilities_sub; /**< notification of vehicle capabilities updates */ + int _offboard_sub; /**< offboard control setpoint subscription */ orb_advert_t _triplet_pub; /**< publish position setpoint triplet */ orb_advert_t _mission_result_pub; /**< publish mission result topic */ @@ -162,6 +164,7 @@ private: struct home_position_s _home_pos; /**< home position for RTL */ struct mission_item_triplet_s _mission_item_triplet; /**< triplet of mission items */ struct mission_result_s _mission_result; /**< mission result for commander/mavlink */ + struct offboard_control_setpoint_s _offboard; /**< offboard control setpoint, to get desired offboard control mode only */ perf_counter_t _loop_perf; /**< loop performance counter */ @@ -383,6 +386,7 @@ Navigator::Navigator() : _offboard_mission_sub(-1), _onboard_mission_sub(-1), _capabilities_sub(-1), + _offboard_sub(-1), /* publications */ _triplet_pub(-1), @@ -422,6 +426,7 @@ Navigator::Navigator() : memset(&_mission_item_triplet.next, 0, sizeof(struct mission_item_s)); memset(&_mission_result, 0, sizeof(struct mission_result_s)); + memset(&_offboard, 0, sizeof(_offboard)); nav_states_str[0] = "NONE"; nav_states_str[1] = "READY"; @@ -591,6 +596,7 @@ Navigator::task_main() _vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); _home_pos_sub = orb_subscribe(ORB_ID(home_position)); + _offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); /* copy all topics first time */ vehicle_status_update(); @@ -1523,12 +1529,49 @@ Navigator::publish_control_mode() case MAIN_STATE_OFFBOARD: _control_mode.flag_control_offboard_enabled = true; _control_mode.flag_control_manual_enabled = false; - _control_mode.flag_control_rates_enabled = false; - _control_mode.flag_control_attitude_enabled = false; - _control_mode.flag_control_altitude_enabled = false; - _control_mode.flag_control_climb_rate_enabled = false; - _control_mode.flag_control_position_enabled = false; - _control_mode.flag_control_velocity_enabled = false; + + switch (_offboard.mode) { + case OFFBOARD_CONTROL_MODE_DIRECT_RATES: + _control_mode.flag_control_rates_enabled = true; + _control_mode.flag_control_attitude_enabled = false; + _control_mode.flag_control_altitude_enabled = false; + _control_mode.flag_control_climb_rate_enabled = false; + _control_mode.flag_control_position_enabled = false; + _control_mode.flag_control_velocity_enabled = false; + break; + case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: + _control_mode.flag_control_rates_enabled = true; + _control_mode.flag_control_attitude_enabled = true; + _control_mode.flag_control_altitude_enabled = false; + _control_mode.flag_control_climb_rate_enabled = false; + _control_mode.flag_control_position_enabled = false; + _control_mode.flag_control_velocity_enabled = false; + break; + case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY: + _control_mode.flag_control_rates_enabled = true; + _control_mode.flag_control_attitude_enabled = true; + _control_mode.flag_control_altitude_enabled = false; + _control_mode.flag_control_climb_rate_enabled = true; + _control_mode.flag_control_position_enabled = false; + _control_mode.flag_control_velocity_enabled = true; + break; + case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: + _control_mode.flag_control_rates_enabled = true; + _control_mode.flag_control_attitude_enabled = true; + _control_mode.flag_control_altitude_enabled = true; + _control_mode.flag_control_climb_rate_enabled = true; + _control_mode.flag_control_position_enabled = true; + _control_mode.flag_control_velocity_enabled = true; + break; + default: + _control_mode.flag_control_rates_enabled = false; + _control_mode.flag_control_attitude_enabled = false; + _control_mode.flag_control_altitude_enabled = false; + _control_mode.flag_control_climb_rate_enabled = false; + _control_mode.flag_control_position_enabled = false; + _control_mode.flag_control_velocity_enabled = false; + break; + } break; default: -- cgit v1.2.3 From 3fe5e88fbe291619783d7bc271a5152d4e42bd3f Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 23 Jan 2014 17:53:55 +0100 Subject: Reverse offboard changes in mc_att_control --- src/modules/mc_att_control/mc_att_control_main.cpp | 99 ++++++++++------------ 1 file changed, 45 insertions(+), 54 deletions(-) diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index c4c6c0138..245ac024b 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -480,73 +480,64 @@ MulticopterAttitudeControl::task_main() float yaw_sp_move_rate = 0.0f; bool publish_att_sp = false; - if (_control_mode.flag_control_offboard_enabled) { - /* offboard control */ - // TODO set _att_sp or _rates_sp here depending on offboard control mode - // TODO _control_mode.flag_control_XXX flags are all false, set it according to ofboard control mode - // but it's not very beautiful, need to think how to do it better - - } else { - /* onboard control */ - /* define which input is the dominating control input */ - if (_control_mode.flag_control_manual_enabled) { - /* manual input */ - if (!_control_mode.flag_control_climb_rate_enabled) { - /* pass throttle directly if not in altitude control mode */ - _att_sp.thrust = _manual.throttle; - } + /* define which input is the dominating control input */ + if (_control_mode.flag_control_manual_enabled) { + /* manual input */ + if (!_control_mode.flag_control_climb_rate_enabled) { + /* pass throttle directly if not in altitude control mode */ + _att_sp.thrust = _manual.throttle; + } - if (!_arming.armed) { - /* reset yaw setpoint when disarmed */ - reset_yaw_sp = true; - } + if (!_arming.armed) { + /* reset yaw setpoint when disarmed */ + reset_yaw_sp = true; + } - if (_control_mode.flag_control_attitude_enabled) { - /* control attitude, update attitude setpoint depending on mode */ - - if (_att_sp.thrust < 0.1f) { - // TODO - //if (_status.condition_landed) { - /* reset yaw setpoint if on ground */ - // reset_yaw_sp = true; - //} - } else { - if (_manual.yaw < -YAW_DEADZONE || YAW_DEADZONE < _manual.yaw) { - /* move yaw setpoint */ - yaw_sp_move_rate = _manual.yaw; - _att_sp.yaw_body = _wrap_pi(_att_sp.yaw_body + yaw_sp_move_rate * dt); - _att_sp.R_valid = false; - publish_att_sp = true; - } - } + if (_control_mode.flag_control_attitude_enabled) { + /* control attitude, update attitude setpoint depending on mode */ - /* reset yaw setpint to current position if needed */ - if (reset_yaw_sp) { - reset_yaw_sp = false; - _att_sp.yaw_body = _att.yaw; + if (_att_sp.thrust < 0.1f) { + // TODO + //if (_status.condition_landed) { + /* reset yaw setpoint if on ground */ + // reset_yaw_sp = true; + //} + } else { + if (_manual.yaw < -YAW_DEADZONE || YAW_DEADZONE < _manual.yaw) { + /* move yaw setpoint */ + yaw_sp_move_rate = _manual.yaw; + _att_sp.yaw_body = _wrap_pi(_att_sp.yaw_body + yaw_sp_move_rate * dt); _att_sp.R_valid = false; publish_att_sp = true; } + } - if (!_control_mode.flag_control_velocity_enabled) { - /* update attitude setpoint if not in position control mode */ - _att_sp.roll_body = _manual.roll; - _att_sp.pitch_body = _manual.pitch; - _att_sp.R_valid = false; - publish_att_sp = true; - } + /* reset yaw setpint to current position if needed */ + if (reset_yaw_sp) { + reset_yaw_sp = false; + _att_sp.yaw_body = _att.yaw; + _att_sp.R_valid = false; + publish_att_sp = true; + } - } else { - /* manual rate inputs (ACRO) */ - // TODO - /* reset yaw setpoint after ACRO */ - reset_yaw_sp = true; + if (!_control_mode.flag_control_velocity_enabled) { + /* update attitude setpoint if not in position control mode */ + _att_sp.roll_body = _manual.roll; + _att_sp.pitch_body = _manual.pitch; + _att_sp.R_valid = false; + publish_att_sp = true; } } else { - /* reset yaw setpoint after non-manual control */ + /* manual rate inputs (ACRO) */ + // TODO + /* reset yaw setpoint after ACRO */ reset_yaw_sp = true; } + + } else { + /* reset yaw setpoint after non-manual control */ + reset_yaw_sp = true; } if (_att_sp.R_valid) { -- cgit v1.2.3 From 6ed6c5bb1fe6cce2c2c784d5f8145c0aa03fabe7 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 23 Jan 2014 17:56:38 +0100 Subject: cammander, navigator: code style fixed --- src/modules/commander/commander.cpp | 26 +- src/modules/commander/state_machine_helper.cpp | 56 ++-- src/modules/navigator/navigator_main.cpp | 352 +++++++++++++++---------- 3 files changed, 258 insertions(+), 176 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index fa815bdfe..bc8278bb7 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -372,6 +372,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe mavlink_log_info(mavlink_fd, "[cmd] HIL: FAILED resetting armed state"); } } + if (hil_ret == OK) ret = true; @@ -406,6 +407,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe arming_res = TRANSITION_NOT_CHANGED; } } + if (arming_res == TRANSITION_CHANGED) ret = true; @@ -454,6 +456,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe } } } + } else { mavlink_log_info(mavlink_fd, "RC signal is valid, ignoring set mode cmd"); } @@ -497,8 +500,9 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe break; case VEHICLE_CMD_OVERRIDE_GOTO: { - // TODO listen vehicle_command topic directly from navigator (?) + // TODO listen vehicle_command topic directly from navigator (?) unsigned int mav_goto = cmd->param1; + if (mav_goto == 0) { // MAV_GOTO_DO_HOLD status->set_nav_state = NAV_STATE_LOITER; status->set_nav_state_timestamp = hrt_absolute_time(); @@ -519,7 +523,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe } break; - /* Flight termination */ + /* Flight termination */ case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command if (armed->armed && cmd->param3 > 0.5) { //xxx: for safety only for now, param3 is unused by VEHICLE_CMD_DO_SET_SERVO @@ -891,6 +895,7 @@ int commander_thread_main(int argc, char *argv[]) if (updated) { orb_copy(ORB_ID(battery_status), battery_sub, &battery); + /* only consider battery voltage if system has been running 2s and battery voltage is valid */ if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) { status.battery_voltage = battery.voltage_filtered_v; @@ -1066,9 +1071,9 @@ int commander_thread_main(int argc, char *argv[]) /* check if left stick is in lower left position and we are in MANUAL or AUTO_READY mode or (ASSISTED mode and landed) -> disarm * do it only for rotary wings */ if (status.is_rotary_wing && - (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) && - (status.main_state == MAIN_STATE_MANUAL || status.condition_landed) && - sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { + (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) && + (status.main_state == MAIN_STATE_MANUAL || status.condition_landed) && + sp_man.yaw < -STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) { /* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */ @@ -1086,7 +1091,7 @@ int commander_thread_main(int argc, char *argv[]) /* check if left stick is in lower right position and we're in MANUAL mode -> arm */ if (status.arming_state == ARMING_STATE_STANDBY && - sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { + sp_man.yaw > STICK_ON_OFF_LIMIT && sp_man.throttle < STICK_THRUST_RANGE * 0.1f) { if (stick_on_counter > STICK_ON_OFF_COUNTER_LIMIT) { if (safety.safety_switch_available && !safety.safety_off) { print_reject_arm("NOT ARMING: Press safety switch first."); @@ -1143,14 +1148,18 @@ int commander_thread_main(int argc, char *argv[]) status.rc_signal_lost = true; status_changed = true; } + if (status.main_state != MAIN_STATE_AUTO && armed.armed) { transition_result_t res = main_state_transition(&status, MAIN_STATE_AUTO); + if (res == TRANSITION_CHANGED) { mavlink_log_critical(mavlink_fd, "#audio: failsafe, switching to RTL mode"); status.set_nav_state = NAV_STATE_RTL; status.set_nav_state_timestamp = hrt_absolute_time(); + } else if (status.main_state != MAIN_STATE_SEATBELT) { res = main_state_transition(&status, MAIN_STATE_SEATBELT); + if (res == TRANSITION_CHANGED) { mavlink_log_critical(mavlink_fd, "#audio: failsafe, switching to SEATBELT mode"); } @@ -1178,13 +1187,16 @@ int commander_thread_main(int argc, char *argv[]) if (offboard_sp.armed && !armed.armed) { if (!safety.safety_switch_available || safety.safety_off) { transition_result_t res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed); + if (res == TRANSITION_CHANGED) { mavlink_log_info(mavlink_fd, "[cmd] ARMED by offboard signal"); } } + } else if (!offboard_sp.armed && armed.armed) { arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); transition_result_t res = arming_state_transition(&status, &safety, new_arming_state, &armed); + if (res == TRANSITION_CHANGED) { mavlink_log_info(mavlink_fd, "[cmd] DISARMED by offboard signal"); } @@ -1202,9 +1214,11 @@ int commander_thread_main(int argc, char *argv[]) /* Flight termination in manual mode if assisted switch is on easy position //xxx hack! */ if (armed.armed && status.main_state == MAIN_STATE_MANUAL && sp_man.assisted_switch > STICK_ON_OFF_LIMIT) { transition_result_t flighttermination_res = flighttermination_state_transition(&status, FLIGHTTERMINATION_STATE_ON); + if (flighttermination_res == TRANSITION_CHANGED) { tune_positive(); } + } else { flighttermination_state_transition(&status, FLIGHTTERMINATION_STATE_OFF); } diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index e5599e1c3..4dd63b5e1 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -67,7 +67,7 @@ static bool flighttermination_state_changed = true; transition_result_t arming_state_transition(struct vehicle_status_s *status, const struct safety_s *safety, - arming_state_t new_arming_state, struct actuator_armed_s *armed) + arming_state_t new_arming_state, struct actuator_armed_s *armed) { /* * Perform an atomic state update @@ -85,6 +85,7 @@ arming_state_transition(struct vehicle_status_s *status, const struct safety_s * /* enforce lockdown in HIL */ if (status->hil_state == HIL_STATE_ON) { armed->lockdown = true; + } else { armed->lockdown = false; } @@ -238,8 +239,8 @@ main_state_transition(struct vehicle_status_s *current_state, main_state_t new_m /* need at minimum altitude estimate */ if (!current_state->is_rotary_wing || - (current_state->condition_local_altitude_valid || - current_state->condition_global_position_valid)) { + (current_state->condition_local_altitude_valid || + current_state->condition_global_position_valid)) { ret = TRANSITION_CHANGED; } @@ -249,7 +250,7 @@ main_state_transition(struct vehicle_status_s *current_state, main_state_t new_m /* need at minimum local position estimate */ if (current_state->condition_local_position_valid || - current_state->condition_global_position_valid) { + current_state->condition_global_position_valid) { ret = TRANSITION_CHANGED; } @@ -373,35 +374,36 @@ transition_result_t flighttermination_state_transition(struct vehicle_status_s * { transition_result_t ret = TRANSITION_DENIED; - /* only check transition if the new state is actually different from the current one */ - if (new_flighttermination_state == status->flighttermination_state) { - ret = TRANSITION_NOT_CHANGED; + /* only check transition if the new state is actually different from the current one */ + if (new_flighttermination_state == status->flighttermination_state) { + ret = TRANSITION_NOT_CHANGED; - } else { + } else { - switch (new_flighttermination_state) { - case FLIGHTTERMINATION_STATE_ON: - ret = TRANSITION_CHANGED; - status->flighttermination_state = FLIGHTTERMINATION_STATE_ON; - warnx("state machine helper: change to FLIGHTTERMINATION_STATE_ON"); - break; - case FLIGHTTERMINATION_STATE_OFF: - ret = TRANSITION_CHANGED; - status->flighttermination_state = FLIGHTTERMINATION_STATE_OFF; - break; + switch (new_flighttermination_state) { + case FLIGHTTERMINATION_STATE_ON: + ret = TRANSITION_CHANGED; + status->flighttermination_state = FLIGHTTERMINATION_STATE_ON; + warnx("state machine helper: change to FLIGHTTERMINATION_STATE_ON"); + break; - default: - break; - } + case FLIGHTTERMINATION_STATE_OFF: + ret = TRANSITION_CHANGED; + status->flighttermination_state = FLIGHTTERMINATION_STATE_OFF; + break; - if (ret == TRANSITION_CHANGED) { - flighttermination_state_changed = true; - // TODO - //control_mode->flag_control_flighttermination_enabled = status->flighttermination_state == FLIGHTTERMINATION_STATE_ON; - } + default: + break; } - return ret; + if (ret == TRANSITION_CHANGED) { + flighttermination_state_changed = true; + // TODO + //control_mode->flag_control_flighttermination_enabled = status->flighttermination_state == FLIGHTTERMINATION_STATE_ON; + } + } + + return ret; } diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index f77c48207..0e317d784 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -167,12 +167,12 @@ private: struct offboard_control_setpoint_s _offboard; /**< offboard control setpoint, to get desired offboard control mode only */ perf_counter_t _loop_perf; /**< loop performance counter */ - + Geofence _geofence; bool _geofence_violation_warning_sent; bool _fence_valid; /**< flag if fence is valid */ - bool _inside_fence; /**< vehicle is inside fence */ + bool _inside_fence; /**< vehicle is inside fence */ struct navigation_capabilities_s _nav_caps; @@ -369,7 +369,7 @@ static const int ERROR = -1; Navigator *g_navigator; } -Navigator::Navigator() : +Navigator::Navigator() : /* state machine transition table */ StateTable(&myTable[0][0], NAV_STATE_MAX, MAX_EVENT), @@ -508,16 +508,20 @@ void Navigator::offboard_mission_update(bool isrotaryWing) { struct mission_s offboard_mission; + if (orb_copy(ORB_ID(mission), _offboard_mission_sub, &offboard_mission) == OK) { /* Check mission feasibility, for now do not handle the return value, * however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */ dm_item_t dm_current; + if (offboard_mission.dataman_id == 0) { dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0; + } else { dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1; } + missionFeasiblityChecker.checkMissionFeasible(isrotaryWing, dm_current, (size_t)offboard_mission.count, _geofence); _mission.set_offboard_dataman_id(offboard_mission.dataman_id); @@ -534,6 +538,7 @@ void Navigator::onboard_mission_update() { struct mission_s onboard_mission; + if (orb_copy(ORB_ID(mission), _onboard_mission_sub, &onboard_mission) == OK) { _mission.set_current_onboard_mission_index(onboard_mission.current_index); @@ -576,11 +581,13 @@ Navigator::task_main() * else clear geofence data in datamanager */ struct stat buffer; - if( stat (GEOFENCE_FILENAME, &buffer) == 0 ) { + + if (stat(GEOFENCE_FILENAME, &buffer) == 0) { warnx("Try to load geofence.txt"); _geofence.loadFromFile(GEOFENCE_FILENAME); + } else { - if (_geofence.clearDm() > 0 ) + if (_geofence.clearDm() > 0) warnx("Geofence cleared"); else warnx("Could not clear geofence"); @@ -597,7 +604,7 @@ Navigator::task_main() _params_sub = orb_subscribe(ORB_ID(parameter_update)); _home_pos_sub = orb_subscribe(ORB_ID(home_position)); _offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); - + /* copy all topics first time */ vehicle_status_update(); parameters_update(); @@ -665,8 +672,9 @@ Navigator::task_main() /* Evaluate state machine from commander and set the navigator mode accordingly */ if (_vstatus.main_state == MAIN_STATE_AUTO && - (_vstatus.arming_state == ARMING_STATE_ARMED || _vstatus.arming_state == ARMING_STATE_ARMED_ERROR)) { + (_vstatus.arming_state == ARMING_STATE_ARMED || _vstatus.arming_state == ARMING_STATE_ARMED_ERROR)) { bool stick_mode = false; + if (!_vstatus.rc_signal_lost) { /* RC signal available, use control switches to set mode */ /* RETURN switch, overrides MISSION switch */ @@ -674,21 +682,27 @@ Navigator::task_main() if (myState != NAV_STATE_READY || _rtl_state != RTL_STATE_LAND) { dispatch(EVENT_RTL_REQUESTED); } + stick_mode = true; + } else { /* MISSION switch */ if (_vstatus.mission_switch == MISSION_SWITCH_LOITER) { dispatch(EVENT_LOITER_REQUESTED); stick_mode = true; + } else if (_vstatus.mission_switch == MISSION_SWITCH_MISSION) { /* switch to mission only if available */ if (_mission.current_mission_available()) { dispatch(EVENT_MISSION_REQUESTED); + } else { dispatch(EVENT_LOITER_REQUESTED); } + stick_mode = true; } + if (!stick_mode && _vstatus.return_switch == RETURN_SWITCH_NORMAL && myState == NAV_STATE_RTL) { /* RETURN switch is in normal mode, no MISSION switch mapped, interrupt if in RTL state */ dispatch(EVENT_LOITER_REQUESTED); @@ -714,15 +728,18 @@ Navigator::task_main() case NAV_STATE_MISSION: if (_mission.current_mission_available()) { dispatch(EVENT_MISSION_REQUESTED); + } else { dispatch(EVENT_LOITER_REQUESTED); } + break; case NAV_STATE_RTL: if (myState != NAV_STATE_READY || _rtl_state != RTL_STATE_LAND) { dispatch(EVENT_RTL_REQUESTED); } + break; default: @@ -735,6 +752,7 @@ Navigator::task_main() if (myState == NAV_STATE_NONE) { if (_mission.current_mission_available()) { dispatch(EVENT_MISSION_REQUESTED); + } else { dispatch(EVENT_LOITER_REQUESTED); } @@ -762,7 +780,7 @@ Navigator::task_main() /* offboard mission updated */ if (fds[4].revents & POLLIN) { offboard_mission_update(_vstatus.is_rotary_wing); - // XXX check if mission really changed + // XXX check if mission really changed dispatch(EVENT_MISSION_CHANGED); } @@ -783,6 +801,7 @@ Navigator::task_main() /* global position updated */ if (fds[1].revents & POLLIN) { global_position_update(); + /* only check if waypoint has been reached in MISSION and RTL modes */ if (myState == NAV_STATE_MISSION || myState == NAV_STATE_RTL) { if (check_mission_item_reached()) { @@ -791,15 +810,15 @@ Navigator::task_main() } /* Check geofence violation */ - if(!_geofence.inside(&_global_pos)) { + if (!_geofence.inside(&_global_pos)) { //xxx: publish geofence violation here (or change local flag depending on which app handles the flight termination) /* Issue a warning about the geofence violation once */ - if (!_geofence_violation_warning_sent) - { + if (!_geofence_violation_warning_sent) { mavlink_log_critical(_mavlink_fd, "#audio: Geofence violation"); _geofence_violation_warning_sent = true; } + } else { /* Reset the _geofence_violation_warning_sent field */ _geofence_violation_warning_sent = false; @@ -849,48 +868,55 @@ Navigator::start() } void -Navigator::status() +Navigator::status() { warnx("Global position is %svalid", _global_pos.valid ? "" : "in"); + if (_global_pos.valid) { warnx("Longitude %5.5f degrees, latitude %5.5f degrees", _global_pos.lon / 1e7d, _global_pos.lat / 1e7d); warnx("Altitude %5.5f meters, altitude above home %5.5f meters", - (double)_global_pos.alt, (double)_global_pos.relative_alt); + (double)_global_pos.alt, (double)_global_pos.relative_alt); warnx("Ground velocity in m/s, x %5.5f, y %5.5f, z %5.5f", - (double)_global_pos.vx, (double)_global_pos.vy, (double)_global_pos.vz); + (double)_global_pos.vx, (double)_global_pos.vy, (double)_global_pos.vz); warnx("Compass heading in degrees %5.5f", (double)(_global_pos.yaw * M_RAD_TO_DEG_F)); } + if (_fence_valid) { warnx("Geofence is valid"); // warnx("Vertex longitude latitude"); // for (unsigned i = 0; i < _fence.count; i++) // warnx("%6u %9.5f %8.5f", i, (double)_fence.vertices[i].lon, (double)_fence.vertices[i].lat); + } else { warnx("Geofence not set"); } switch (myState) { - case NAV_STATE_NONE: - warnx("State: None"); - break; - case NAV_STATE_LOITER: - warnx("State: Loiter"); - break; - case NAV_STATE_MISSION: - warnx("State: Mission"); - break; - case NAV_STATE_RTL: - warnx("State: RTL"); - break; - default: - warnx("State: Unknown"); - break; + case NAV_STATE_NONE: + warnx("State: None"); + break; + + case NAV_STATE_LOITER: + warnx("State: Loiter"); + break; + + case NAV_STATE_MISSION: + warnx("State: Mission"); + break; + + case NAV_STATE_RTL: + warnx("State: RTL"); + break; + + default: + warnx("State: Unknown"); + break; } } StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = { - { - /* STATE_NONE */ + { + /* STATE_NONE */ /* EVENT_NONE_REQUESTED */ {NO_ACTION, NAV_STATE_NONE}, /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY}, /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER}, @@ -899,8 +925,8 @@ StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = { /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_NONE}, /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_NONE}, }, - { - /* STATE_READY */ + { + /* STATE_READY */ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE}, /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_READY}, /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_READY}, @@ -910,7 +936,7 @@ StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = { /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_READY}, }, { - /* STATE_LOITER */ + /* STATE_LOITER */ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE}, /* EVENT_READY_REQUESTED */ {NO_ACTION, NAV_STATE_LOITER}, /* EVENT_LOITER_REQUESTED */ {NO_ACTION, NAV_STATE_LOITER}, @@ -919,8 +945,8 @@ StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = { /* EVENT_MISSION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER}, /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_LOITER}, }, - { - /* STATE_MISSION */ + { + /* STATE_MISSION */ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE}, /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY}, /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER}, @@ -929,8 +955,8 @@ StateTable::Tran const Navigator::myTable[NAV_STATE_MAX][MAX_EVENT] = { /* EVENT_MISSION_CHANGED */ {ACTION(&Navigator::start_mission), NAV_STATE_MISSION}, /* EVENT_HOME_POSITION_CHANGED */ {NO_ACTION, NAV_STATE_MISSION}, }, - { - /* STATE_RTL */ + { + /* STATE_RTL */ /* EVENT_NONE_REQUESTED */ {ACTION(&Navigator::start_none), NAV_STATE_NONE}, /* EVENT_READY_REQUESTED */ {ACTION(&Navigator::start_ready), NAV_STATE_READY}, /* EVENT_LOITER_REQUESTED */ {ACTION(&Navigator::start_loiter), NAV_STATE_LOITER}, @@ -993,6 +1019,7 @@ Navigator::start_loiter() if (_global_pos.alt < min_alt_amsl) { _mission_item_triplet.current.altitude = min_alt_amsl; mavlink_log_info(_mavlink_fd, "[navigator] loiter %.1fm higher", (double)(min_alt_amsl - _global_pos.alt)); + } else { _mission_item_triplet.current.altitude = _global_pos.alt; mavlink_log_info(_mavlink_fd, "[navigator] loiter at current altitude"); @@ -1043,27 +1070,28 @@ Navigator::set_mission_item() add_home_pos_to_rtl(&_mission_item_triplet.current); if (_mission_item_triplet.current.nav_cmd != NAV_CMD_RETURN_TO_LAUNCH && - _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_TIME_LIMIT && - _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_TURN_COUNT && - _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_UNLIMITED) { + _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_TIME_LIMIT && + _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_TURN_COUNT && + _mission_item_triplet.current.nav_cmd != NAV_CMD_LOITER_UNLIMITED) { /* don't reset RTL state on RTL or LOITER items */ _rtl_state = RTL_STATE_NONE; } if (_vstatus.is_rotary_wing) { if (_need_takeoff && ( - _mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF || - _mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT || - _mission_item_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH || - _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT || - _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT || - _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED - )) { + _mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF || + _mission_item_triplet.current.nav_cmd == NAV_CMD_WAYPOINT || + _mission_item_triplet.current.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH || + _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT || + _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_TURN_COUNT || + _mission_item_triplet.current.nav_cmd == NAV_CMD_LOITER_UNLIMITED + )) { /* do special TAKEOFF handling for VTOL */ _need_takeoff = false; /* calculate desired takeoff altitude AMSL */ float takeoff_alt_amsl = _mission_item_triplet.current.altitude; + if (_mission_item_triplet.current.altitude_is_relative) takeoff_alt_amsl += _home_pos.altitude; @@ -1089,6 +1117,7 @@ Navigator::set_mission_item() _mission_item_triplet.current.altitude = takeoff_alt_amsl; _mission_item_triplet.current.altitude_is_relative = false; } + } else if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) { /* will need takeoff after landing */ _need_takeoff = true; @@ -1097,13 +1126,16 @@ Navigator::set_mission_item() if (_do_takeoff) { mavlink_log_info(_mavlink_fd, "[navigator] takeoff to %.1fm", _mission_item_triplet.current.altitude); + } else { if (onboard) { mavlink_log_info(_mavlink_fd, "[navigator] heading to onboard WP %d", index); + } else { mavlink_log_info(_mavlink_fd, "[navigator] heading to offboard WP %d", index); } } + } else { /* since a mission is not advanced without WPs available, this is not supposed to happen */ _mission_item_triplet.current_valid = false; @@ -1116,6 +1148,7 @@ Navigator::set_mission_item() if (ret == OK) { add_home_pos_to_rtl(&_mission_item_triplet.next); _mission_item_triplet.next_valid = true; + } else { /* this will fail for the last WP */ _mission_item_triplet.next_valid = false; @@ -1129,17 +1162,21 @@ void Navigator::start_rtl() { _do_takeoff = false; + if (_rtl_state == RTL_STATE_NONE) { if (_global_pos.alt < _home_pos.altitude + _parameters.rtl_alt) { _rtl_state = RTL_STATE_CLIMB; + } else { _rtl_state = RTL_STATE_RETURN; + if (_reset_loiter_pos) { _mission_item_triplet.current.altitude_is_relative = false; _mission_item_triplet.current.altitude = _global_pos.alt; } } } + _reset_loiter_pos = true; mavlink_log_info(_mavlink_fd, "[navigator] RTL started"); set_rtl_item(); @@ -1150,107 +1187,112 @@ Navigator::set_rtl_item() { switch (_rtl_state) { case RTL_STATE_CLIMB: { - memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s)); - _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid; + memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s)); + _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid; - _mission_item_triplet.current_valid = true; - _mission_item_triplet.next_valid = false; + _mission_item_triplet.current_valid = true; + _mission_item_triplet.next_valid = false; - float climb_alt = _home_pos.altitude + _parameters.rtl_alt; - if (_vstatus.condition_landed) - climb_alt = fmaxf(climb_alt, _global_pos.alt + _parameters.rtl_alt); + float climb_alt = _home_pos.altitude + _parameters.rtl_alt; + + if (_vstatus.condition_landed) + climb_alt = fmaxf(climb_alt, _global_pos.alt + _parameters.rtl_alt); + + _mission_item_triplet.current.altitude_is_relative = false; + _mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7d; + _mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7d; + _mission_item_triplet.current.altitude = climb_alt; + _mission_item_triplet.current.yaw = NAN; + _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; + _mission_item_triplet.current.loiter_direction = 1; + _mission_item_triplet.current.nav_cmd = NAV_CMD_TAKEOFF; + _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius; + _mission_item_triplet.current.time_inside = 0.0f; + _mission_item_triplet.current.pitch_min = 0.0f; + _mission_item_triplet.current.autocontinue = true; + _mission_item_triplet.current.origin = ORIGIN_ONBOARD; + mavlink_log_info(_mavlink_fd, "[navigator] RTL: climb to %.1fm", climb_alt - _home_pos.altitude); + break; + } - _mission_item_triplet.current.altitude_is_relative = false; - _mission_item_triplet.current.lat = (double)_global_pos.lat / 1e7d; - _mission_item_triplet.current.lon = (double)_global_pos.lon / 1e7d; - _mission_item_triplet.current.altitude = climb_alt; - _mission_item_triplet.current.yaw = NAN; - _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; - _mission_item_triplet.current.loiter_direction = 1; - _mission_item_triplet.current.nav_cmd = NAV_CMD_TAKEOFF; - _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius; - _mission_item_triplet.current.time_inside = 0.0f; - _mission_item_triplet.current.pitch_min = 0.0f; - _mission_item_triplet.current.autocontinue = true; - _mission_item_triplet.current.origin = ORIGIN_ONBOARD; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: climb to %.1fm", climb_alt - _home_pos.altitude); - break; - } case RTL_STATE_RETURN: { - memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s)); - _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid; + memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s)); + _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid; + + _mission_item_triplet.current_valid = true; + _mission_item_triplet.next_valid = false; + + _mission_item_triplet.current.lat = _home_pos.lat; + _mission_item_triplet.current.lon = _home_pos.lon; + // don't change altitude setpoint + _mission_item_triplet.current.yaw = NAN; + _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; + _mission_item_triplet.current.loiter_direction = 1; + _mission_item_triplet.current.nav_cmd = NAV_CMD_WAYPOINT; + _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius; + _mission_item_triplet.current.time_inside = 0.0f; + _mission_item_triplet.current.pitch_min = 0.0f; + _mission_item_triplet.current.autocontinue = true; + _mission_item_triplet.current.origin = ORIGIN_ONBOARD; + mavlink_log_info(_mavlink_fd, "[navigator] RTL: return"); + break; + } - _mission_item_triplet.current_valid = true; - _mission_item_triplet.next_valid = false; - - _mission_item_triplet.current.lat = _home_pos.lat; - _mission_item_triplet.current.lon = _home_pos.lon; - // don't change altitude setpoint - _mission_item_triplet.current.yaw = NAN; - _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; - _mission_item_triplet.current.loiter_direction = 1; - _mission_item_triplet.current.nav_cmd = NAV_CMD_WAYPOINT; - _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius; - _mission_item_triplet.current.time_inside = 0.0f; - _mission_item_triplet.current.pitch_min = 0.0f; - _mission_item_triplet.current.autocontinue = true; - _mission_item_triplet.current.origin = ORIGIN_ONBOARD; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: return"); - break; - } case RTL_STATE_DESCEND: { - memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s)); - _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid; + memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s)); + _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid; - _mission_item_triplet.current_valid = true; - _mission_item_triplet.next_valid = false; + _mission_item_triplet.current_valid = true; + _mission_item_triplet.next_valid = false; - float descend_alt = _home_pos.altitude + _parameters.land_alt; + float descend_alt = _home_pos.altitude + _parameters.land_alt; + + _mission_item_triplet.current.altitude_is_relative = false; + _mission_item_triplet.current.lat = _home_pos.lat; + _mission_item_triplet.current.lon = _home_pos.lon; + _mission_item_triplet.current.altitude = descend_alt; + _mission_item_triplet.current.yaw = NAN; + _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; + _mission_item_triplet.current.loiter_direction = 1; + _mission_item_triplet.current.nav_cmd = NAV_CMD_WAYPOINT; + _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius; + _mission_item_triplet.current.time_inside = 0.0f; + _mission_item_triplet.current.pitch_min = 0.0f; + _mission_item_triplet.current.autocontinue = true; + _mission_item_triplet.current.origin = ORIGIN_ONBOARD; + mavlink_log_info(_mavlink_fd, "[navigator] RTL: descend to %.1fm", descend_alt - _home_pos.altitude); + break; + } - _mission_item_triplet.current.altitude_is_relative = false; - _mission_item_triplet.current.lat = _home_pos.lat; - _mission_item_triplet.current.lon = _home_pos.lon; - _mission_item_triplet.current.altitude = descend_alt; - _mission_item_triplet.current.yaw = NAN; - _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; - _mission_item_triplet.current.loiter_direction = 1; - _mission_item_triplet.current.nav_cmd = NAV_CMD_WAYPOINT; - _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius; - _mission_item_triplet.current.time_inside = 0.0f; - _mission_item_triplet.current.pitch_min = 0.0f; - _mission_item_triplet.current.autocontinue = true; - _mission_item_triplet.current.origin = ORIGIN_ONBOARD; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: descend to %.1fm", descend_alt - _home_pos.altitude); - break; - } case RTL_STATE_LAND: { - memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s)); - _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid; + memcpy(&_mission_item_triplet.previous, &_mission_item_triplet.current, sizeof(mission_item_s)); + _mission_item_triplet.previous_valid = _mission_item_triplet.current_valid; - _mission_item_triplet.current_valid = true; - _mission_item_triplet.next_valid = false; + _mission_item_triplet.current_valid = true; + _mission_item_triplet.next_valid = false; + + _mission_item_triplet.current.altitude_is_relative = false; + _mission_item_triplet.current.lat = _home_pos.lat; + _mission_item_triplet.current.lon = _home_pos.lon; + _mission_item_triplet.current.altitude = _home_pos.altitude; + _mission_item_triplet.current.yaw = NAN; + _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; + _mission_item_triplet.current.loiter_direction = 1; + _mission_item_triplet.current.nav_cmd = NAV_CMD_LAND; + _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius; + _mission_item_triplet.current.time_inside = 0.0f; + _mission_item_triplet.current.pitch_min = 0.0f; + _mission_item_triplet.current.autocontinue = true; + _mission_item_triplet.current.origin = ORIGIN_ONBOARD; + mavlink_log_info(_mavlink_fd, "[navigator] RTL: land"); + break; + } - _mission_item_triplet.current.altitude_is_relative = false; - _mission_item_triplet.current.lat = _home_pos.lat; - _mission_item_triplet.current.lon = _home_pos.lon; - _mission_item_triplet.current.altitude = _home_pos.altitude; - _mission_item_triplet.current.yaw = NAN; - _mission_item_triplet.current.loiter_radius = _parameters.loiter_radius; - _mission_item_triplet.current.loiter_direction = 1; - _mission_item_triplet.current.nav_cmd = NAV_CMD_LAND; - _mission_item_triplet.current.acceptance_radius = _parameters.acceptance_radius; - _mission_item_triplet.current.time_inside = 0.0f; - _mission_item_triplet.current.pitch_min = 0.0f; - _mission_item_triplet.current.autocontinue = true; - _mission_item_triplet.current.origin = ORIGIN_ONBOARD; - mavlink_log_info(_mavlink_fd, "[navigator] RTL: land"); - break; - } default: { - mavlink_log_critical(_mavlink_fd, "[navigator] error: unknown RTL state: %d", _rtl_state); - start_loiter(); - break; - } + mavlink_log_critical(_mavlink_fd, "[navigator] error: unknown RTL state: %d", _rtl_state); + start_loiter(); + break; + } } publish_mission_item_triplet(); @@ -1267,6 +1309,7 @@ Navigator::check_mission_item_reached() if (_mission_item_triplet.current.nav_cmd == NAV_CMD_LAND) { if (_vstatus.is_rotary_wing) { return _vstatus.condition_landed; + } else { /* For fw there is currently no landing detector: * make sure control is not stopped when overshooting the landing waypoint */ @@ -1281,7 +1324,7 @@ Navigator::check_mission_item_reached() _mission_item_triplet.current.loiter_radius > 0.01f) { return false; - } + } uint64_t now = hrt_absolute_time(); @@ -1301,18 +1344,20 @@ Navigator::check_mission_item_reached() /* current relative or AMSL altitude depending on mission item altitude_is_relative flag */ float wp_alt_amsl = _mission_item_triplet.current.altitude; + if (_mission_item_triplet.current.altitude_is_relative) _mission_item_triplet.current.altitude += _home_pos.altitude; dist = get_distance_to_point_global_wgs84(_mission_item_triplet.current.lat, _mission_item_triplet.current.lon, wp_alt_amsl, - (double)_global_pos.lat / 1e7d, (double)_global_pos.lon / 1e7d, _global_pos.alt, - &dist_xy, &dist_z); + (double)_global_pos.lat / 1e7d, (double)_global_pos.lon / 1e7d, _global_pos.alt, + &dist_xy, &dist_z); if (_do_takeoff) { if (_global_pos.alt > wp_alt_amsl - acceptance_radius) { /* require only altitude for takeoff */ _waypoint_position_reached = true; } + } else { if (dist >= 0.0f && dist <= acceptance_radius) { _waypoint_position_reached = true; @@ -1324,9 +1369,11 @@ Navigator::check_mission_item_reached() if (_vstatus.is_rotary_wing && !_do_takeoff && isfinite(_mission_item_triplet.current.yaw)) { /* check yaw if defined only for rotary wing except takeoff */ float yaw_err = _wrap_pi(_mission_item_triplet.current.yaw - _global_pos.yaw); + if (fabsf(yaw_err) < 0.05f) { /* XXX get rid of magic number */ _waypoint_yaw_reached = true; } + } else { _waypoint_yaw_reached = true; } @@ -1336,20 +1383,22 @@ Navigator::check_mission_item_reached() if (_waypoint_position_reached && _waypoint_yaw_reached) { if (_time_first_inside_orbit == 0) { _time_first_inside_orbit = now; + if (_mission_item_triplet.current.time_inside > 0.01f) { mavlink_log_info(_mavlink_fd, "[navigator] waypoint reached, wait for %.1fs", _mission_item_triplet.current.time_inside); } } - + /* check if the MAV was long enough inside the waypoint orbit */ if ((now - _time_first_inside_orbit >= (uint64_t)_mission_item_triplet.current.time_inside * 1e6) - || _mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) { + || _mission_item_triplet.current.nav_cmd == NAV_CMD_TAKEOFF) { _time_first_inside_orbit = 0; _waypoint_yaw_reached = false; _waypoint_position_reached = false; return true; } } + return false; } @@ -1362,6 +1411,7 @@ Navigator::on_mission_item_reached() /* takeoff completed */ _do_takeoff = false; mavlink_log_info(_mavlink_fd, "[navigator] takeoff completed"); + } else { /* advance by one mission item */ _mission.move_to_next(); @@ -1369,23 +1419,28 @@ Navigator::on_mission_item_reached() if (_mission.current_mission_available()) { set_mission_item(); + } else { /* if no more mission items available then finish mission */ /* loiter at last waypoint */ _reset_loiter_pos = false; mavlink_log_info(_mavlink_fd, "[navigator] mission completed"); + if (_vstatus.condition_landed) { dispatch(EVENT_READY_REQUESTED); + } else { dispatch(EVENT_LOITER_REQUESTED); } } + } else { /* RTL finished */ if (_rtl_state == RTL_STATE_LAND) { /* landed at home position */ mavlink_log_info(_mavlink_fd, "[navigator] RTL completed, landed"); dispatch(EVENT_READY_REQUESTED); + } else { /* next RTL step */ _rtl_state = (RTLState)(_rtl_state + 1); @@ -1508,6 +1563,7 @@ Navigator::publish_control_mode() case MAIN_STATE_AUTO: _control_mode.flag_control_offboard_enabled = false; _control_mode.flag_control_manual_enabled = false; + if (myState == NAV_STATE_READY) { /* disable all controllers, armed but idle */ _control_mode.flag_control_rates_enabled = false; @@ -1516,6 +1572,7 @@ Navigator::publish_control_mode() _control_mode.flag_control_velocity_enabled = false; _control_mode.flag_control_altitude_enabled = false; _control_mode.flag_control_climb_rate_enabled = false; + } else { _control_mode.flag_control_rates_enabled = true; _control_mode.flag_control_attitude_enabled = true; @@ -1524,6 +1581,7 @@ Navigator::publish_control_mode() _control_mode.flag_control_altitude_enabled = true; _control_mode.flag_control_climb_rate_enabled = true; } + break; case MAIN_STATE_OFFBOARD: @@ -1539,6 +1597,7 @@ Navigator::publish_control_mode() _control_mode.flag_control_position_enabled = false; _control_mode.flag_control_velocity_enabled = false; break; + case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: _control_mode.flag_control_rates_enabled = true; _control_mode.flag_control_attitude_enabled = true; @@ -1547,6 +1606,7 @@ Navigator::publish_control_mode() _control_mode.flag_control_position_enabled = false; _control_mode.flag_control_velocity_enabled = false; break; + case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY: _control_mode.flag_control_rates_enabled = true; _control_mode.flag_control_attitude_enabled = true; @@ -1555,6 +1615,7 @@ Navigator::publish_control_mode() _control_mode.flag_control_position_enabled = false; _control_mode.flag_control_velocity_enabled = true; break; + case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: _control_mode.flag_control_rates_enabled = true; _control_mode.flag_control_attitude_enabled = true; @@ -1563,6 +1624,7 @@ Navigator::publish_control_mode() _control_mode.flag_control_position_enabled = true; _control_mode.flag_control_velocity_enabled = true; break; + default: _control_mode.flag_control_rates_enabled = false; _control_mode.flag_control_attitude_enabled = false; @@ -1572,6 +1634,7 @@ Navigator::publish_control_mode() _control_mode.flag_control_velocity_enabled = false; break; } + break; default: @@ -1591,7 +1654,8 @@ Navigator::publish_control_mode() } } -bool Navigator::cmp_mission_item_equivalent(const struct mission_item_s a, const struct mission_item_s b) { +bool Navigator::cmp_mission_item_equivalent(const struct mission_item_s a, const struct mission_item_s b) +{ if (a.altitude_is_relative == b.altitude_is_relative && fabs(a.lat - b.lat) < FLT_EPSILON && fabs(a.lon - b.lon) < FLT_EPSILON && @@ -1604,6 +1668,7 @@ bool Navigator::cmp_mission_item_equivalent(const struct mission_item_s a, const fabsf(a.time_inside - b.time_inside) < FLT_EPSILON && a.autocontinue == b.autocontinue) { return true; + } else { return false; } @@ -1664,8 +1729,9 @@ int navigator_main(int argc, char *argv[]) } else if (!strcmp(argv[1], "fence")) { navigator::g_navigator->add_fence_point(argc - 2, argv + 2); + } else if (!strcmp(argv[1], "fencefile")) { - navigator::g_navigator->load_fence_from_file(GEOFENCE_FILENAME); + navigator::g_navigator->load_fence_from_file(GEOFENCE_FILENAME); } else { usage(); -- cgit v1.2.3 From dfedbcb855e53da5fe2ce4d37d9f4fba54626d62 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Fri, 24 Jan 2014 23:56:54 +0000 Subject: added check for MAIN_STATE_OFFBOARD @#1152 so that we dont get thrown out of this state --- src/modules/commander/commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index bc8278bb7..bec6884e2 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1149,7 +1149,7 @@ int commander_thread_main(int argc, char *argv[]) status_changed = true; } - if (status.main_state != MAIN_STATE_AUTO && armed.armed) { + if (status.main_state != MAIN_STATE_AUTO && armed.armed && status.main_state != MAIN_STATE_OFFBOARD) { transition_result_t res = main_state_transition(&status, MAIN_STATE_AUTO); if (res == TRANSITION_CHANGED) { -- cgit v1.2.3 From a037861ec21834428416e92482feacad749e1cd3 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Mon, 27 Jan 2014 14:33:34 +0000 Subject: Added method to update _offboard in navigator_main.cpp --- src/modules/navigator/navigator_main.cpp | 21 ++++++++++++++++++++- 1 file changed, 20 insertions(+), 1 deletion(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 0e317d784..829511053 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -271,6 +271,11 @@ private: * Retrieve vehicle status */ void vehicle_status_update(); + + /** + * Retrieve offboard setpoint + */ + void offboard_update(); /** @@ -503,6 +508,11 @@ Navigator::navigation_capabilities_update() orb_copy(ORB_ID(navigation_capabilities), _capabilities_sub, &_nav_caps); } +void +Navigator::offboard_update() +{ + orb_copy(ORB_ID(offboard_control_setpoint), _offboard_sub, &_offboard); +} void Navigator::offboard_mission_update(bool isrotaryWing) @@ -613,6 +623,7 @@ Navigator::task_main() navigation_capabilities_update(); offboard_mission_update(_vstatus.is_rotary_wing); onboard_mission_update(); + offboard_update(); /* rate limit position updates to 50 Hz */ orb_set_interval(_global_pos_sub, 20); @@ -623,7 +634,7 @@ Navigator::task_main() const hrt_abstime mavlink_open_interval = 500000; /* wakeup source(s) */ - struct pollfd fds[7]; + struct pollfd fds[8]; /* Setup of loop */ fds[0].fd = _params_sub; @@ -640,6 +651,9 @@ Navigator::task_main() fds[5].events = POLLIN; fds[6].fd = _vstatus_sub; fds[6].events = POLLIN; + fds[7].fd = _offboard_sub; + fds[7].events = POLLIN; + while (!_task_should_exit) { @@ -825,6 +839,11 @@ Navigator::task_main() } } + /* offboard setpoint updated */ + if (fds[7].revents & POLLIN) { + offboard_update(); + } + /* notify user about state changes */ if (myState != prevState) { mavlink_log_info(_mavlink_fd, "[navigator] nav state: %s -> %s", nav_states_str[prevState], nav_states_str[myState]); -- cgit v1.2.3 From 59a5f37b7feb0cecfdd983e88ce55931f3c1bce1 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Wed, 29 Jan 2014 15:39:58 +0000 Subject: Added check for offboard_control_signal_lost when switching to offboard mode with rc switch --- src/modules/commander/commander.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index bec6884e2..3687f55fb 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1478,8 +1478,8 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta if (!isfinite(sp_man->offboard_switch)) { current_status->offboard_switch = OFFBOARD_SWITCH_NONE; - } else if (sp_man->offboard_switch > STICK_ON_OFF_LIMIT) { - current_status->offboard_switch = OFFBOARD_SWITCH_OFFBOARD; + } else if (sp_man->offboard_switch > STICK_ON_OFF_LIMIT && !status.offboard_control_signal_lost) { + current_status->offboard_switch = OFFBOARD_SWITCH_OFFBOARD; } else { current_status->offboard_switch = OFFBOARD_SWITCH_ONBOARD; -- cgit v1.2.3 From 01c9092213449c761759bcda11ef9613226be713 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 29 Jan 2014 18:06:03 +0100 Subject: Revert "Added check for offboard_control_signal_lost when switching to offboard mode with rc switch" This reverts commit 59a5f37b7feb0cecfdd983e88ce55931f3c1bce1. --- src/modules/commander/commander.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 3687f55fb..bec6884e2 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1478,8 +1478,8 @@ check_mode_switches(struct manual_control_setpoint_s *sp_man, struct vehicle_sta if (!isfinite(sp_man->offboard_switch)) { current_status->offboard_switch = OFFBOARD_SWITCH_NONE; - } else if (sp_man->offboard_switch > STICK_ON_OFF_LIMIT && !status.offboard_control_signal_lost) { - current_status->offboard_switch = OFFBOARD_SWITCH_OFFBOARD; + } else if (sp_man->offboard_switch > STICK_ON_OFF_LIMIT) { + current_status->offboard_switch = OFFBOARD_SWITCH_OFFBOARD; } else { current_status->offboard_switch = OFFBOARD_SWITCH_ONBOARD; -- cgit v1.2.3 From 8ab94150db31e270b34cecaa4701628df873042c Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 6 Feb 2014 20:23:23 +0100 Subject: commander: print_reject_mode() bug fixed --- src/modules/commander/commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 246efd61e..2c2b680b4 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1624,7 +1624,7 @@ set_main_state_rc(struct vehicle_status_s *status) if (status->offboard_switch == OFFBOARD_SWITCH_OFFBOARD) { res = main_state_transition(status, MAIN_STATE_OFFBOARD); if (res == TRANSITION_DENIED) { - print_reject_mode("OFFBOARD"); + print_reject_mode(status, "OFFBOARD"); } else { return res; -- cgit v1.2.3 From 15ea9cd401351f7487cff35333780d6d4ff47e09 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Fri, 14 Feb 2014 12:37:10 +0000 Subject: minor cosmetic changes --- src/modules/commander/commander.cpp | 1 - src/modules/mavlink/mavlink_receiver.cpp | 10 ++++------ 2 files changed, 4 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 3687f55fb..3e5d9dcf6 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1491,7 +1491,6 @@ check_main_state_machine(struct vehicle_status_s *current_status) { /* evaluate the main state machine */ transition_result_t res = TRANSITION_DENIED; - if (current_status->offboard_switch == OFFBOARD_SWITCH_OFFBOARD) { /* offboard switch overrides main switch */ res = main_state_transition(current_status, MAIN_STATE_OFFBOARD); diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 62597d91a..f3345b35f 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -288,23 +288,21 @@ handle_message(mavlink_message_t *msg) ml_armed = false; break; - case 1: + case OFFBOARD_CONTROL_MODE_DIRECT_RATES: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES; ml_armed = true; - break; - case 2: + case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; ml_armed = true; - break; - case 3: + case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY; break; - case 4: + case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION; break; } -- cgit v1.2.3 From 66f270dd7e2a8668ae7a4f3387e5098381eff84d Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 14 Feb 2014 13:39:57 +0100 Subject: commander: double subscribing to offboard setpoint fixed --- src/modules/commander/commander.cpp | 15 +++------------ 1 file changed, 3 insertions(+), 12 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 2c2b680b4..bf7bf2ef3 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -761,11 +761,6 @@ int commander_thread_main(int argc, char *argv[]) struct manual_control_setpoint_s sp_man; memset(&sp_man, 0, sizeof(sp_man)); - /* Subscribe to offboard control data */ - int offboard_sp_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); - struct offboard_control_setpoint_s offboard_sp; - memset(&offboard_sp, 0, sizeof(offboard_sp)); - /* Subscribe to offboard control data */ int sp_offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); struct offboard_control_setpoint_s sp_offboard; @@ -883,10 +878,6 @@ int commander_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(manual_control_setpoint), sp_man_sub, &sp_man); } - if (updated) { - orb_copy(ORB_ID(offboard_control_setpoint), offboard_sp_sub, &offboard_sp); - } - orb_check(sp_offboard_sub, &updated); if (updated) { @@ -1285,7 +1276,7 @@ int commander_thread_main(int argc, char *argv[]) } /* check offboard signal */ - if (offboard_sp.timestamp != 0 && hrt_absolute_time() < offboard_sp.timestamp + OFFBOARD_TIMEOUT) { + if (sp_offboard.timestamp != 0 && hrt_absolute_time() < sp_offboard.timestamp + OFFBOARD_TIMEOUT) { if (!status.offboard_control_signal_found_once) { status.offboard_control_signal_found_once = true; mavlink_log_info(mavlink_fd, "[cmd] detected offboard signal first time"); @@ -1301,7 +1292,7 @@ int commander_thread_main(int argc, char *argv[]) status.offboard_control_signal_lost = false; if (status.main_state == MAIN_STATE_OFFBOARD) { - if (offboard_sp.armed && !armed.armed) { + if (sp_offboard.armed && !armed.armed) { if (!safety.safety_switch_available || safety.safety_off) { transition_result_t res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed); @@ -1310,7 +1301,7 @@ int commander_thread_main(int argc, char *argv[]) } } - } else if (!offboard_sp.armed && armed.armed) { + } else if (!sp_offboard.armed && armed.armed) { arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); transition_result_t res = arming_state_transition(&status, &safety, new_arming_state, &armed); -- cgit v1.2.3 From 08055e5d52b8c522ca86e86bc161343dc396e5d9 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Mon, 17 Feb 2014 11:45:51 +0000 Subject: added examples/jetdrive_control(copy of mc_att_control) --- .gitignore | 6 + makefiles/config_px4fmu-v2_default.mk | 1 + src/examples/jetdrive_control/jetdrive_control.h | 207 +++++++ .../jetdrive_control/jetdrive_control_main.cpp | 678 +++++++++++++++++++++ .../jetdrive_control/jetdrive_control_params.c | 56 ++ src/examples/jetdrive_control/module.mk | 41 ++ 6 files changed, 989 insertions(+) create mode 100644 src/examples/jetdrive_control/jetdrive_control.h create mode 100644 src/examples/jetdrive_control/jetdrive_control_main.cpp create mode 100644 src/examples/jetdrive_control/jetdrive_control_params.c create mode 100644 src/examples/jetdrive_control/module.mk diff --git a/.gitignore b/.gitignore index 3e94cf620..63f0a70b7 100644 --- a/.gitignore +++ b/.gitignore @@ -35,3 +35,9 @@ mavlink/include/mavlink/v0.9/ /Documentation/doxygen*objdb*tmp .tags .tags_sorted_by_file +*.creator +*.includes +*.files +*.config +*.user +*.autosave diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index 2ad2f63a9..ca740a79f 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -141,6 +141,7 @@ MODULES += examples/px4_simple_app # Tutorial code from # https://pixhawk.ethz.ch/px4/dev/example_fixedwing_control #MODULES += examples/fixedwing_control +MODULES += examples/jetdrive_control # Hardware test #MODULES += examples/hwtest diff --git a/src/examples/jetdrive_control/jetdrive_control.h b/src/examples/jetdrive_control/jetdrive_control.h new file mode 100644 index 000000000..06c986092 --- /dev/null +++ b/src/examples/jetdrive_control/jetdrive_control.h @@ -0,0 +1,207 @@ +#ifndef JETDRIVE_CONTROL_H +#define JETDRIVE_CONTROL_H + + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + + +/** + * Multicopter attitude control app start / stop handling function + * + * @ingroup apps + */ +extern "C" __EXPORT int jetdrive_control_main(int argc, char *argv[]); + +#define MIN_TAKEOFF_THROTTLE 0.3f +#define YAW_DEADZONE 0.05f +#define RATES_I_LIMIT 0.5f + +class JetdriveControl +{ +public: + /** + * Constructor + */ + JetdriveControl(); + + /** + * Destructor, also kills the sensors task. + */ + ~JetdriveControl(); + + /** + * Start the sensors task. + * + * @return OK on success. + */ + int start(); + +private: + + bool _task_should_exit; /**< if true, sensor task should exit */ + int _control_task; /**< task handle for sensor task */ + + int _v_att_sub; /**< vehicle attitude subscription */ + int _v_att_sp_sub; /**< vehicle attitude setpoint subscription */ + int _v_rates_sp_sub; /**< vehicle rates setpoint subscription */ + int _v_control_mode_sub; /**< vehicle control mode subscription */ + int _params_sub; /**< parameter updates subscription */ + int _manual_control_sp_sub; /**< manual control setpoint subscription */ + int _armed_sub; /**< arming status subscription */ + + orb_advert_t _att_sp_pub; /**< attitude setpoint publication */ + orb_advert_t _v_rates_sp_pub; /**< rate setpoint publication */ + orb_advert_t _actuators_0_pub; /**< attitude actuator controls publication */ + + struct vehicle_attitude_s _v_att; /**< vehicle attitude */ + struct vehicle_attitude_setpoint_s _v_att_sp; /**< vehicle attitude setpoint */ + struct vehicle_rates_setpoint_s _v_rates_sp; /**< vehicle rates setpoint */ + struct manual_control_setpoint_s _manual_control_sp; /**< manual control setpoint */ + struct vehicle_control_mode_s _v_control_mode; /**< vehicle control mode */ + struct actuator_controls_s _actuators; /**< actuator controls */ + struct actuator_armed_s _armed; /**< actuator arming status */ + + perf_counter_t _loop_perf; /**< loop performance counter */ + + math::Matrix<3, 3> _R_sp; /**< attitude setpoint rotation matrix */ + math::Matrix<3, 3> _R; /**< rotation matrix for current state */ + math::Vector<3> _rates_prev; /**< angular rates on previous step */ + math::Vector<3> _rates_sp; /**< angular rates setpoint */ + math::Vector<3> _rates_int; /**< angular rates integral error */ + float _thrust_sp; /**< thrust setpoint */ + math::Vector<3> _att_control; /**< attitude control vector */ + + math::Matrix<3, 3> I; /**< identity matrix */ + + bool _reset_yaw_sp; /**< reset yaw setpoint flag */ + + struct { + param_t roll_p; + param_t roll_rate_p; + param_t roll_rate_i; + param_t roll_rate_d; + param_t pitch_p; + param_t pitch_rate_p; + param_t pitch_rate_i; + param_t pitch_rate_d; + param_t yaw_p; + param_t yaw_rate_p; + param_t yaw_rate_i; + param_t yaw_rate_d; + param_t yaw_ff; + + param_t rc_scale_yaw; + } _params_handles; /**< handles for interesting parameters */ + + struct { + math::Vector<3> att_p; /**< P gain for angular error */ + math::Vector<3> rate_p; /**< P gain for angular rate error */ + math::Vector<3> rate_i; /**< I gain for angular rate error */ + math::Vector<3> rate_d; /**< D gain for angular rate error */ + float yaw_ff; /**< yaw control feed-forward */ + + float rc_scale_yaw; + } _params; + + /** + * Update our local parameter cache. + */ + int parameters_update(); + + /** + * Check for parameter update and handle it. + */ + void parameter_update_poll(); + + /** + * Check for changes in vehicle control mode. + */ + void vehicle_control_mode_poll(); + + /** + * Check for changes in manual inputs. + */ + void vehicle_manual_poll(); + + /** + * Check for attitude setpoint updates. + */ + void vehicle_attitude_setpoint_poll(); + + /** + * Check for rates setpoint updates. + */ + void vehicle_rates_setpoint_poll(); + + /** + * Check for arming status updates. + */ + void arming_status_poll(); + + /** + * Attitude controller. + */ + void control_attitude(float dt); + + /** + * Attitude rates controller. + */ + void control_attitude_rates(float dt); + + /** + * Shim for calling task_main from task_create. + */ + static void task_main_trampoline(int argc, char *argv[]); + + /** + * Main sensor collection task. + */ + void task_main() __attribute__((noreturn)); +}; + + +#ifndef jetdrive_control +#define jetdrive_control + +namespace jetdrive_control +{ + +/* oddly, ERROR is not defined for c++ */ +#ifdef ERROR +# undef ERROR +#endif +static const int ERROR = -1; + +JetdriveControl *g_control; +} + +#endif // jetdrive_control + +#endif // JETDRIVE_CONTROL_H diff --git a/src/examples/jetdrive_control/jetdrive_control_main.cpp b/src/examples/jetdrive_control/jetdrive_control_main.cpp new file mode 100644 index 000000000..b66b9c214 --- /dev/null +++ b/src/examples/jetdrive_control/jetdrive_control_main.cpp @@ -0,0 +1,678 @@ +/**************************************************************************** + * + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. + * Author: @author Tobias Naegeli + * @author Lorenz Meier + * @author Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mc_att_control_main.c + * Multicopter attitude controller. + * + * The controller has two loops: P loop for angular error and PD loop for angular rate error. + * Desired rotation calculated keeping in mind that yaw response is normally slower than roll/pitch. + * For small deviations controller rotates copter to have shortest path of thrust vector and independently rotates around yaw, + * so actual rotation axis is not constant. For large deviations controller rotates copter around fixed axis. + * These two approaches fused seamlessly with weight depending on angular error. + * When thrust vector directed near-horizontally (e.g. roll ~= PI/2) yaw setpoint ignored because of singularity. + * Controller doesn't use Euler angles for work, they generated only for more human-friendly control and logging. + * If rotation matrix setpoint is invalid it will be generated from Euler angles for compatibility with old position controllers. + */ + +#include "jetdrive_control.h" + + + +JetdriveControl::JetdriveControl() : + + _task_should_exit(false), + _control_task(-1), + +/* subscriptions */ + _v_att_sub(-1), + _v_att_sp_sub(-1), + _v_control_mode_sub(-1), + _params_sub(-1), + _manual_control_sp_sub(-1), + _armed_sub(-1), + +/* publications */ + _att_sp_pub(-1), + _v_rates_sp_pub(-1), + _actuators_0_pub(-1), + +/* performance counters */ + _loop_perf(perf_alloc(PC_ELAPSED, "fw att control")) + +{ + memset(&_v_att, 0, sizeof(_v_att)); + memset(&_v_att_sp, 0, sizeof(_v_att_sp)); + memset(&_manual_control_sp, 0, sizeof(_manual_control_sp)); + memset(&_v_control_mode, 0, sizeof(_v_control_mode)); + memset(&_armed, 0, sizeof(_armed)); + + _params.att_p.zero(); + _params.rate_p.zero(); + _params.rate_i.zero(); + _params.rate_d.zero(); + + _R_sp.identity(); + _R.identity(); + _rates_prev.zero(); + _rates_sp.zero(); + _rates_int.zero(); + _thrust_sp = 0.0f; + _att_control.zero(); + + I.identity(); + + _params_handles.roll_p = param_find("MC_ROLL_P"); + _params_handles.roll_rate_p = param_find("MC_ROLLRATE_P"); + _params_handles.roll_rate_i = param_find("MC_ROLLRATE_I"); + _params_handles.roll_rate_d = param_find("MC_ROLLRATE_D"); + _params_handles.pitch_p = param_find("MC_PITCH_P"); + _params_handles.pitch_rate_p = param_find("MC_PITCHRATE_P"); + _params_handles.pitch_rate_i = param_find("MC_PITCHRATE_I"); + _params_handles.pitch_rate_d = param_find("MC_PITCHRATE_D"); + _params_handles.yaw_p = param_find("MC_YAW_P"); + _params_handles.yaw_rate_p = param_find("MC_YAWRATE_P"); + _params_handles.yaw_rate_i = param_find("MC_YAWRATE_I"); + _params_handles.yaw_rate_d = param_find("MC_YAWRATE_D"); + _params_handles.yaw_ff = param_find("MC_YAW_FF"); + + _params_handles.rc_scale_yaw = param_find("RC_SCALE_YAW"); + + /* fetch initial parameter values */ + parameters_update(); +} + +JetdriveControl::~JetdriveControl() +{ + if (_control_task != -1) { + /* task wakes up every 100ms or so at the longest */ + _task_should_exit = true; + + /* wait for a second for the task to quit at our request */ + unsigned i = 0; + + do { + /* wait 20ms */ + usleep(20000); + + /* if we have given up, kill it */ + if (++i > 50) { + task_delete(_control_task); + break; + } + } while (_control_task != -1); + } + + jetdrive_control::g_control = nullptr; +} + +int +JetdriveControl::parameters_update() +{ + float v; + + /* roll */ + param_get(_params_handles.roll_p, &v); + _params.att_p(0) = v; + param_get(_params_handles.roll_rate_p, &v); + _params.rate_p(0) = v; + param_get(_params_handles.roll_rate_i, &v); + _params.rate_i(0) = v; + param_get(_params_handles.roll_rate_d, &v); + _params.rate_d(0) = v; + + /* pitch */ + param_get(_params_handles.pitch_p, &v); + _params.att_p(1) = v; + param_get(_params_handles.pitch_rate_p, &v); + _params.rate_p(1) = v; + param_get(_params_handles.pitch_rate_i, &v); + _params.rate_i(1) = v; + param_get(_params_handles.pitch_rate_d, &v); + _params.rate_d(1) = v; + + /* yaw */ + param_get(_params_handles.yaw_p, &v); + _params.att_p(2) = v; + param_get(_params_handles.yaw_rate_p, &v); + _params.rate_p(2) = v; + param_get(_params_handles.yaw_rate_i, &v); + _params.rate_i(2) = v; + param_get(_params_handles.yaw_rate_d, &v); + _params.rate_d(2) = v; + + param_get(_params_handles.yaw_ff, &_params.yaw_ff); + + param_get(_params_handles.rc_scale_yaw, &_params.rc_scale_yaw); + + return OK; +} + +void +JetdriveControl::parameter_update_poll() +{ + bool updated; + + /* Check HIL state if vehicle status has changed */ + orb_check(_params_sub, &updated); + + if (updated) { + struct parameter_update_s param_update; + orb_copy(ORB_ID(parameter_update), _params_sub, ¶m_update); + parameters_update(); + } +} + +void +JetdriveControl::vehicle_control_mode_poll() +{ + bool updated; + + /* Check HIL state if vehicle status has changed */ + orb_check(_v_control_mode_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(vehicle_control_mode), _v_control_mode_sub, &_v_control_mode); + } +} + +void +JetdriveControl::vehicle_manual_poll() +{ + bool updated; + + /* get pilots inputs */ + orb_check(_manual_control_sp_sub, &updated); + + if (updated) { + + orb_copy(ORB_ID(manual_control_setpoint), _manual_control_sp_sub, &_manual_control_sp); + } +} + +void +JetdriveControl::vehicle_attitude_setpoint_poll() +{ + /* check if there is a new setpoint */ + bool updated; + orb_check(_v_att_sp_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(vehicle_attitude_setpoint), _v_att_sp_sub, &_v_att_sp); + } +} + +void +JetdriveControl::vehicle_rates_setpoint_poll() +{ + /* check if there is a new setpoint */ + bool updated; + orb_check(_v_rates_sp_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(vehicle_rates_setpoint), _v_rates_sp_sub, &_v_rates_sp); + } +} + +void +JetdriveControl::arming_status_poll() +{ + /* check if there is a new setpoint */ + bool updated; + orb_check(_armed_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); + } +} + +/* + * Attitude controller. + * Input: 'manual_control_setpoint' and 'vehicle_attitude_setpoint' topics (depending on mode) + * Output: '_rates_sp' vector, '_thrust_sp', 'vehicle_attitude_setpoint' topic (for manual modes) + */ +void +JetdriveControl::control_attitude(float dt) +{ + float yaw_sp_move_rate = 0.0f; + bool publish_att_sp = false; + + if (_v_control_mode.flag_control_manual_enabled) { + /* manual input, set or modify attitude setpoint */ + + if (_v_control_mode.flag_control_velocity_enabled || _v_control_mode.flag_control_climb_rate_enabled) { + /* in assisted modes poll 'vehicle_attitude_setpoint' topic and modify it */ + vehicle_attitude_setpoint_poll(); + } + + if (!_v_control_mode.flag_control_climb_rate_enabled) { + /* pass throttle directly if not in altitude stabilized mode */ + _v_att_sp.thrust = _manual_control_sp.throttle; + publish_att_sp = true; + } + + if (!_armed.armed) { + /* reset yaw setpoint when disarmed */ + _reset_yaw_sp = true; + } + + /* move yaw setpoint in all modes */ + if (_v_att_sp.thrust < 0.1f) { + // TODO + //if (_status.condition_landed) { + /* reset yaw setpoint if on ground */ + // reset_yaw_sp = true; + //} + } else { + float yaw_dz_scaled = YAW_DEADZONE * _params.rc_scale_yaw; + + if (_params.rc_scale_yaw > 0.001f && fabs(_manual_control_sp.yaw) > yaw_dz_scaled) { + /* move yaw setpoint */ + yaw_sp_move_rate = _manual_control_sp.yaw / _params.rc_scale_yaw; + + if (_manual_control_sp.yaw > 0.0f) { + yaw_sp_move_rate -= YAW_DEADZONE; + + } else { + yaw_sp_move_rate += YAW_DEADZONE; + } + + yaw_sp_move_rate *= _params.rc_scale_yaw; + _v_att_sp.yaw_body = _wrap_pi(_v_att_sp.yaw_body + yaw_sp_move_rate * dt); + _v_att_sp.R_valid = false; + publish_att_sp = true; + } + } + + /* reset yaw setpint to current position if needed */ + if (_reset_yaw_sp) { + _reset_yaw_sp = false; + _v_att_sp.yaw_body = _v_att.yaw; + _v_att_sp.R_valid = false; + publish_att_sp = true; + } + + if (!_v_control_mode.flag_control_velocity_enabled) { + /* update attitude setpoint if not in position control mode */ + _v_att_sp.roll_body = _manual_control_sp.roll; + _v_att_sp.pitch_body = _manual_control_sp.pitch; + _v_att_sp.R_valid = false; + publish_att_sp = true; + } + + } else { + /* in non-manual mode use 'vehicle_attitude_setpoint' topic */ + vehicle_attitude_setpoint_poll(); + + /* reset yaw setpoint after non-manual control mode */ + _reset_yaw_sp = true; + } + + _thrust_sp = _v_att_sp.thrust; + + /* construct attitude setpoint rotation matrix */ + if (_v_att_sp.R_valid) { + /* rotation matrix in _att_sp is valid, use it */ + _R_sp.set(&_v_att_sp.R_body[0][0]); + + } else { + /* rotation matrix in _att_sp is not valid, use euler angles instead */ + _R_sp.from_euler(_v_att_sp.roll_body, _v_att_sp.pitch_body, _v_att_sp.yaw_body); + + /* copy rotation matrix back to setpoint struct */ + memcpy(&_v_att_sp.R_body[0][0], &_R_sp.data[0][0], sizeof(_v_att_sp.R_body)); + _v_att_sp.R_valid = true; + } + + /* publish the attitude setpoint if needed */ + if (publish_att_sp) { + _v_att_sp.timestamp = hrt_absolute_time(); + + if (_att_sp_pub > 0) { + orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_v_att_sp); + + } else { + _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_v_att_sp); + } + } + + /* rotation matrix for current state */ + _R.set(_v_att.R); + + /* all input data is ready, run controller itself */ + + /* try to move thrust vector shortest way, because yaw response is slower than roll/pitch */ + math::Vector<3> R_z(_R(0, 2), _R(1, 2), _R(2, 2)); + math::Vector<3> R_sp_z(_R_sp(0, 2), _R_sp(1, 2), _R_sp(2, 2)); + + /* axis and sin(angle) of desired rotation */ + math::Vector<3> e_R = _R.transposed() * (R_z % R_sp_z); + + /* calculate angle error */ + float e_R_z_sin = e_R.length(); + float e_R_z_cos = R_z * R_sp_z; + + /* calculate weight for yaw control */ + float yaw_w = _R_sp(2, 2) * _R_sp(2, 2); + + /* calculate rotation matrix after roll/pitch only rotation */ + math::Matrix<3, 3> R_rp; + + if (e_R_z_sin > 0.0f) { + /* get axis-angle representation */ + float e_R_z_angle = atan2f(e_R_z_sin, e_R_z_cos); + math::Vector<3> e_R_z_axis = e_R / e_R_z_sin; + + e_R = e_R_z_axis * e_R_z_angle; + + /* cross product matrix for e_R_axis */ + math::Matrix<3, 3> e_R_cp; + e_R_cp.zero(); + e_R_cp(0, 1) = -e_R_z_axis(2); + e_R_cp(0, 2) = e_R_z_axis(1); + e_R_cp(1, 0) = e_R_z_axis(2); + e_R_cp(1, 2) = -e_R_z_axis(0); + e_R_cp(2, 0) = -e_R_z_axis(1); + e_R_cp(2, 1) = e_R_z_axis(0); + + /* rotation matrix for roll/pitch only rotation */ + R_rp = _R * (I + e_R_cp * e_R_z_sin + e_R_cp * e_R_cp * (1.0f - e_R_z_cos)); + + } else { + /* zero roll/pitch rotation */ + R_rp = _R; + } + + /* R_rp and _R_sp has the same Z axis, calculate yaw error */ + math::Vector<3> R_sp_x(_R_sp(0, 0), _R_sp(1, 0), _R_sp(2, 0)); + math::Vector<3> R_rp_x(R_rp(0, 0), R_rp(1, 0), R_rp(2, 0)); + e_R(2) = atan2f((R_rp_x % R_sp_x) * R_sp_z, R_rp_x * R_sp_x) * yaw_w; + + if (e_R_z_cos < 0.0f) { + /* for large thrust vector rotations use another rotation method: + * calculate angle and axis for R -> R_sp rotation directly */ + math::Quaternion q; + q.from_dcm(_R.transposed() * _R_sp); + math::Vector<3> e_R_d = q.imag(); + e_R_d.normalize(); + e_R_d *= 2.0f * atan2f(e_R_d.length(), q(0)); + + /* use fusion of Z axis based rotation and direct rotation */ + float direct_w = e_R_z_cos * e_R_z_cos * yaw_w; + e_R = e_R * (1.0f - direct_w) + e_R_d * direct_w; + } + + /* calculate angular rates setpoint */ + _rates_sp = _params.att_p.emult(e_R); + + /* feed forward yaw setpoint rate */ + _rates_sp(2) += yaw_sp_move_rate * yaw_w * _params.yaw_ff; +} + +/* + * Attitude rates controller. + * Input: '_rates_sp' vector, '_thrust_sp' + * Output: '_att_control' vector + */ +void +JetdriveControl::control_attitude_rates(float dt) +{ + /* reset integral if disarmed */ + if (!_armed.armed) { + _rates_int.zero(); + } + + /* current body angular rates */ + math::Vector<3> rates; + rates(0) = _v_att.rollspeed; + rates(1) = _v_att.pitchspeed; + rates(2) = _v_att.yawspeed; + + /* angular rates error */ + math::Vector<3> rates_err = _rates_sp - rates; + _att_control = _params.rate_p.emult(rates_err) + _params.rate_d.emult(_rates_prev - rates) / dt + _rates_int; + _rates_prev = rates; + + /* update integral only if not saturated on low limit */ + if (_thrust_sp > 0.1f) { + for (int i = 0; i < 3; i++) { + if (fabsf(_att_control(i)) < _thrust_sp) { + float rate_i = _rates_int(i) + _params.rate_i(i) * rates_err(i) * dt; + + if (isfinite(rate_i) && rate_i > -RATES_I_LIMIT && rate_i < RATES_I_LIMIT && + _att_control(i) > -RATES_I_LIMIT && _att_control(i) < RATES_I_LIMIT) { + _rates_int(i) = rate_i; + } + } + } + } +} + +void +JetdriveControl::task_main_trampoline(int argc, char *argv[]) +{ + jetdrive_control::g_control->task_main(); +} + +void +JetdriveControl::task_main() +{ + warnx("started"); + fflush(stdout); + + /* + * do subscriptions + */ + _v_att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); + _v_rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint)); + _v_att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); + _v_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); + _params_sub = orb_subscribe(ORB_ID(parameter_update)); + _manual_control_sp_sub = orb_subscribe(ORB_ID(manual_control_setpoint)); + _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); + + /* rate limit attitude updates to 200Hz, failsafe against spam, normally runs at the same rate as attitude estimator */ + orb_set_interval(_v_att_sub, 5); + + /* initialize parameters cache */ + parameters_update(); + + /* wakeup source: vehicle attitude */ + struct pollfd fds[1]; + + fds[0].fd = _v_att_sub; + fds[0].events = POLLIN; + + while (!_task_should_exit) { + + /* wait for up to 100ms for data */ + int pret = poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); + + /* timed out - periodic check for _task_should_exit */ + if (pret == 0) + continue; + + /* this is undesirable but not much we can do - might want to flag unhappy status */ + if (pret < 0) { + warn("poll error %d, %d", pret, errno); + /* sleep a bit before next try */ + usleep(100000); + continue; + } + + perf_begin(_loop_perf); + + /* run controller on attitude changes */ + if (fds[0].revents & POLLIN) { + static uint64_t last_run = 0; + float dt = (hrt_absolute_time() - last_run) / 1000000.0f; + last_run = hrt_absolute_time(); + + /* guard against too small (< 2ms) and too large (> 20ms) dt's */ + if (dt < 0.002f) { + dt = 0.002f; + + } else if (dt > 0.02f) { + dt = 0.02f; + } + + /* copy attitude topic */ + orb_copy(ORB_ID(vehicle_attitude), _v_att_sub, &_v_att); + + /* check for updates in other topics */ + parameter_update_poll(); + vehicle_control_mode_poll(); + arming_status_poll(); + vehicle_manual_poll(); + + if (_v_control_mode.flag_control_attitude_enabled) { + control_attitude(dt); + + /* publish attitude rates setpoint */ + _v_rates_sp.roll = _rates_sp(0); + _v_rates_sp.pitch = _rates_sp(1); + _v_rates_sp.yaw = _rates_sp(2); + _v_rates_sp.thrust = _thrust_sp; + _v_rates_sp.timestamp = hrt_absolute_time(); + + if (_v_rates_sp_pub > 0) { + orb_publish(ORB_ID(vehicle_rates_setpoint), _v_rates_sp_pub, &_v_rates_sp); + + } else { + _v_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_v_rates_sp); + } + + } else { + /* attitude controller disabled */ + // TODO poll 'attitude_rates_setpoint' topic + _rates_sp.zero(); + _thrust_sp = 0.0f; + } + + if (_v_control_mode.flag_control_rates_enabled) { + control_attitude_rates(dt); + + /* publish actuator controls */ + _actuators.control[0] = (isfinite(_att_control(0))) ? _att_control(0) : 0.0f; + _actuators.control[1] = (isfinite(_att_control(1))) ? _att_control(1) : 0.0f; + _actuators.control[2] = (isfinite(_att_control(2))) ? _att_control(2) : 0.0f; + _actuators.control[3] = (isfinite(_thrust_sp)) ? _thrust_sp : 0.0f; + _actuators.timestamp = hrt_absolute_time(); + + if (_actuators_0_pub > 0) { + orb_publish(ORB_ID(actuator_controls_0), _actuators_0_pub, &_actuators); + + } else { + _actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators); + } + } + } + + perf_end(_loop_perf); + } + + warnx("exit"); + + _control_task = -1; + _exit(0); +} + +int +JetdriveControl::start() +{ + ASSERT(_control_task == -1); + + /* start the task */ + _control_task = task_spawn_cmd("jetdrive_control", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 5, + 2048, + (main_t)&JetdriveControl::task_main_trampoline, + nullptr); + + if (_control_task < 0) { + warn("task start failed"); + return -errno; + } + + return OK; +} + +int jetdrive_control_main(int argc, char *argv[]) +{ + if (argc < 1) + errx(1, "usage: jetdrive_control {start|stop|status}"); + + if (!strcmp(argv[1], "start")) { + + if (jetdrive_control::g_control != nullptr) + errx(1, "already running"); + + jetdrive_control::g_control = new JetdriveControl; + + if (jetdrive_control::g_control == nullptr) + errx(1, "alloc failed"); + + if (OK != jetdrive_control::g_control->start()) { + delete jetdrive_control::g_control; + jetdrive_control::g_control = nullptr; + err(1, "start failed"); + } + + exit(0); + } + + if (!strcmp(argv[1], "stop")) { + if (jetdrive_control::g_control == nullptr) + errx(1, "not running"); + + delete jetdrive_control::g_control; + jetdrive_control::g_control = nullptr; + exit(0); + } + + if (!strcmp(argv[1], "status")) { + if (jetdrive_control::g_control) { + errx(0, "running"); + + } else { + errx(1, "not running"); + } + } + + warnx("unrecognized command"); + return 1; +} diff --git a/src/examples/jetdrive_control/jetdrive_control_params.c b/src/examples/jetdrive_control/jetdrive_control_params.c new file mode 100644 index 000000000..27a45b6bb --- /dev/null +++ b/src/examples/jetdrive_control/jetdrive_control_params.c @@ -0,0 +1,56 @@ +/**************************************************************************** + * + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. + * Author: @author Tobias Naegeli + * @author Lorenz Meier + * @author Anton Babushkin + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mc_att_control_params.c + * Parameters for multicopter attitude controller. + */ + +#include + +PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.0f); +PARAM_DEFINE_FLOAT(MC_ROLLRATE_P, 0.1f); +PARAM_DEFINE_FLOAT(MC_ROLLRATE_I, 0.0f); +PARAM_DEFINE_FLOAT(MC_ROLLRATE_D, 0.002f); +PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.0f); +PARAM_DEFINE_FLOAT(MC_PITCHRATE_P, 0.1f); +PARAM_DEFINE_FLOAT(MC_PITCHRATE_I, 0.0f); +PARAM_DEFINE_FLOAT(MC_PITCHRATE_D, 0.002f); +PARAM_DEFINE_FLOAT(MC_YAW_P, 2.0f); +PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f); +PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f); +PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f); +PARAM_DEFINE_FLOAT(MC_YAW_FF, 0.5f); diff --git a/src/examples/jetdrive_control/module.mk b/src/examples/jetdrive_control/module.mk new file mode 100644 index 000000000..2d1025451 --- /dev/null +++ b/src/examples/jetdrive_control/module.mk @@ -0,0 +1,41 @@ +############################################################################ +# +# Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# Multirotor attitude controller (vector based, no Euler singularities) +# + +MODULE_COMMAND = jetdrive_control + +SRCS = jetdrive_control_main.cpp \ + jetdrive_control_params.c -- cgit v1.2.3 From e8bee868e2386b5ce9fc2bc4b8ca6aa63f240232 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 16:50:00 +0400 Subject: commander: publish vehicle_control_mode for OFFBOARD state --- src/modules/commander/commander.cpp | 32 ++++++++++++++++++++++---- src/modules/mavlink/mavlink_receiver.cpp | 1 + src/modules/uORB/topics/vehicle_control_mode.h | 1 + 3 files changed, 30 insertions(+), 4 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 1b9ca6988..61ef63921 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -159,6 +159,7 @@ static struct vehicle_status_s status; static struct actuator_armed_s armed; static struct safety_s safety; static struct vehicle_control_mode_s control_mode; +static struct offboard_control_setpoint_s sp_offboard; /* tasks waiting for low prio thread */ typedef enum { @@ -767,7 +768,6 @@ int commander_thread_main(int argc, char *argv[]) /* Subscribe to offboard control data */ int sp_offboard_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); - struct offboard_control_setpoint_s sp_offboard; memset(&sp_offboard, 0, sizeof(sp_offboard)); /* Subscribe to global position */ @@ -1691,6 +1691,8 @@ set_control_mode() control_mode.flag_external_manual_override_ok = !status.is_rotary_wing; control_mode.flag_system_hil_enabled = status.hil_state == HIL_STATE_ON; + control_mode.flag_control_auto_enabled = false; + control_mode.flag_control_offboard_enabled = false; control_mode.flag_control_termination_enabled = false; /* set this flag when navigator should act */ @@ -1701,7 +1703,6 @@ set_control_mode() switch (status.main_state) { case MAIN_STATE_MANUAL: control_mode.flag_control_manual_enabled = true; - control_mode.flag_control_auto_enabled = false; control_mode.flag_control_rates_enabled = status.is_rotary_wing; control_mode.flag_control_attitude_enabled = status.is_rotary_wing; control_mode.flag_control_altitude_enabled = false; @@ -1712,7 +1713,6 @@ set_control_mode() case MAIN_STATE_SEATBELT: control_mode.flag_control_manual_enabled = true; - control_mode.flag_control_auto_enabled = false; control_mode.flag_control_rates_enabled = true; control_mode.flag_control_attitude_enabled = true; control_mode.flag_control_altitude_enabled = true; @@ -1723,7 +1723,6 @@ set_control_mode() case MAIN_STATE_EASY: control_mode.flag_control_manual_enabled = true; - control_mode.flag_control_auto_enabled = false; control_mode.flag_control_rates_enabled = true; control_mode.flag_control_attitude_enabled = true; control_mode.flag_control_altitude_enabled = true; @@ -1735,6 +1734,31 @@ set_control_mode() case MAIN_STATE_AUTO: navigator_enabled = true; + case MAIN_STATE_OFFBOARD: + control_mode.flag_control_manual_enabled = false; + control_mode.flag_control_offboard_enabled = false; + + switch (sp_offboard.mode) { + case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = true; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_position_enabled = false; + control_mode.flag_control_velocity_enabled = false; + break; + + default: + control_mode.flag_control_rates_enabled = false; + control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_position_enabled = false; + control_mode.flag_control_velocity_enabled = false; + } + + break; + default: break; } diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 0ca64853a..735bc50da 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -330,6 +330,7 @@ handle_message(mavlink_message_t *msg) orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp); } + // TODO use vehicle_control_mode.flag_control_offboard_enabled if (v_status.main_state == MAIN_STATE_OFFBOARD) { /* in offboard mode also publish setpoint directly */ switch (offboard_control_sp.mode) { diff --git a/src/modules/uORB/topics/vehicle_control_mode.h b/src/modules/uORB/topics/vehicle_control_mode.h index 7cbb37cd8..5444c4ebf 100644 --- a/src/modules/uORB/topics/vehicle_control_mode.h +++ b/src/modules/uORB/topics/vehicle_control_mode.h @@ -74,6 +74,7 @@ struct vehicle_control_mode_s bool flag_control_manual_enabled; /**< true if manual input is mixed in */ bool flag_control_auto_enabled; /**< true if onboard autopilot should act */ + bool flag_control_offboard_enabled; /**< true if offboard control should be used */ bool flag_control_rates_enabled; /**< true if rates are stabilized */ bool flag_control_attitude_enabled; /**< true if attitude stabilization is mixed in */ bool flag_control_velocity_enabled; /**< true if horizontal velocity (implies direction) is controlled */ -- cgit v1.2.3 From 172c82c258819c6f2d95b85b56c41015f928b282 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 17:21:43 +0400 Subject: commander: vehicle_control_mode fixes --- src/modules/commander/commander.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index f82c8c35b..1ef872e39 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1736,7 +1736,7 @@ set_control_mode() case MAIN_STATE_OFFBOARD: control_mode.flag_control_manual_enabled = false; - control_mode.flag_control_offboard_enabled = false; + control_mode.flag_control_offboard_enabled = true; switch (sp_offboard.mode) { case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: @@ -1776,7 +1776,6 @@ set_control_mode() case FAILSAFE_STATE_TERMINATION: /* disable all controllers on termination */ control_mode.flag_control_manual_enabled = false; - control_mode.flag_control_auto_enabled = false; control_mode.flag_control_rates_enabled = false; control_mode.flag_control_attitude_enabled = false; control_mode.flag_control_position_enabled = false; -- cgit v1.2.3 From 3b270fbdab60c0fac1c76dff170b0a9b6f494e8d Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 17 Feb 2014 18:07:12 +0400 Subject: commander: auto arm/disarm by offboard thrust "feature" removed --- src/modules/commander/commander.cpp | 20 -------------------- 1 file changed, 20 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 1ef872e39..4a69318c9 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1295,26 +1295,6 @@ int commander_thread_main(int argc, char *argv[]) status.offboard_control_signal_lost = false; - if (status.main_state == MAIN_STATE_OFFBOARD) { - if (sp_offboard.armed && !armed.armed) { - if (!safety.safety_switch_available || safety.safety_off) { - transition_result_t res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed); - - if (res == TRANSITION_CHANGED) { - mavlink_log_info(mavlink_fd, "[cmd] ARMED by offboard signal"); - } - } - - } else if (!sp_offboard.armed && armed.armed) { - arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); - transition_result_t res = arming_state_transition(&status, &safety, new_arming_state, &armed); - - if (res == TRANSITION_CHANGED) { - mavlink_log_info(mavlink_fd, "[cmd] DISARMED by offboard signal"); - } - } - } - } else { if (!status.offboard_control_signal_lost) { mavlink_log_critical(mavlink_fd, "[cmd[ CRITICAL: OFFBOARD SIGNAL LOST"); -- cgit v1.2.3 From 9c20f86899b17dc6cd1e7642a6212e370474345e Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Tue, 18 Feb 2014 11:10:52 +0000 Subject: lalala --- src/modules/mavlink/mavlink_receiver.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 735bc50da..b724447c5 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -330,7 +330,13 @@ handle_message(mavlink_message_t *msg) orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp); } - // TODO use vehicle_control_mode.flag_control_offboard_enabled + static struct vehicle_control_mode_s _v_control_mode; + memset(&_v_control_mode, 0, sizeof(_v_control_mode)); + + /**< vehicle control mode subscription */ + static int _v_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); + + // TODO use vehicle_control_mode.flag_control_offboard_enabled if (v_status.main_state == MAIN_STATE_OFFBOARD) { /* in offboard mode also publish setpoint directly */ switch (offboard_control_sp.mode) { -- cgit v1.2.3 From 92e15b83cc565cab149b7a8103794672dc82dcb5 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Wed, 26 Feb 2014 11:24:32 +0000 Subject: added subscriber to vehicle_control_mode --- src/modules/mavlink/mavlink_receiver.cpp | 23 +++++++++++++++-------- 1 file changed, 15 insertions(+), 8 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index b724447c5..8ea0f9ea3 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -98,6 +98,7 @@ static struct vehicle_vicon_position_s vicon_position; static struct vehicle_command_s vcmd; static struct offboard_control_setpoint_s offboard_control_sp; static struct vehicle_attitude_setpoint_s att_sp; +static struct vehicle_control_mode_s _v_control_mode; struct vehicle_global_position_s hil_global_pos; struct vehicle_local_position_s hil_local_pos; @@ -117,6 +118,8 @@ static orb_advert_t pub_hil_baro = -1; static orb_advert_t pub_hil_airspeed = -1; static orb_advert_t pub_hil_battery = -1; +static int _v_control_mode_sub = -1; + /* packet counter */ static int hil_counter = 0; static int hil_frames = 0; @@ -330,14 +333,14 @@ handle_message(mavlink_message_t *msg) orb_publish(ORB_ID(offboard_control_setpoint), offboard_control_sp_pub, &offboard_control_sp); } - static struct vehicle_control_mode_s _v_control_mode; - memset(&_v_control_mode, 0, sizeof(_v_control_mode)); - - /**< vehicle control mode subscription */ - static int _v_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); - - // TODO use vehicle_control_mode.flag_control_offboard_enabled - if (v_status.main_state == MAIN_STATE_OFFBOARD) { + // TODO use vehicle_control_mode.flag_control_offboard_enabled + bool updated; + orb_check(_v_control_mode_sub, &updated); + if (updated) { + orb_copy(ORB_ID(vehicle_control_mode), _v_control_mode_sub, &_v_control_mode); + } + if(_v_control_mode.flag_control_offboard_enabled) { +// if (v_status.main_state == MAIN_STATE_OFFBOARD) { /* in offboard mode also publish setpoint directly */ switch (offboard_control_sp.mode) { case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: @@ -863,6 +866,10 @@ receive_thread(void *arg) ssize_t nread = 0; + // vehicle control mode subscription + memset(&_v_control_mode, 0, sizeof(_v_control_mode)); + _v_control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); + while (!thread_should_exit) { if (poll(fds, 1, timeout) > 0) { if (nread < sizeof(buf)) { -- cgit v1.2.3 From 1acd951173212fcb3d7511792270609b748528d7 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Wed, 26 Feb 2014 11:26:15 +0000 Subject: added publish to actuators when _v_control_mode.flag_external_manual_override_ok flag is set --- .../jetdrive_control/jetdrive_control_main.cpp | 77 ++++++++++++++-------- 1 file changed, 48 insertions(+), 29 deletions(-) diff --git a/src/examples/jetdrive_control/jetdrive_control_main.cpp b/src/examples/jetdrive_control/jetdrive_control_main.cpp index b66b9c214..d91f89401 100644 --- a/src/examples/jetdrive_control/jetdrive_control_main.cpp +++ b/src/examples/jetdrive_control/jetdrive_control_main.cpp @@ -558,45 +558,64 @@ JetdriveControl::task_main() arming_status_poll(); vehicle_manual_poll(); - if (_v_control_mode.flag_control_attitude_enabled) { - control_attitude(dt); - - /* publish attitude rates setpoint */ - _v_rates_sp.roll = _rates_sp(0); - _v_rates_sp.pitch = _rates_sp(1); - _v_rates_sp.yaw = _rates_sp(2); - _v_rates_sp.thrust = _thrust_sp; - _v_rates_sp.timestamp = hrt_absolute_time(); + if(_v_control_mode.flag_external_manual_override_ok) + { + /* manual/direct control */ + _actuators.control[0] = _manual_control_sp .roll; + _actuators.control[1] = _manual_control_sp.pitch; + _actuators.control[2] = _manual_control_sp.yaw; + _actuators.control[3] = _manual_control_sp.throttle; + _actuators.timestamp = hrt_absolute_time(); - if (_v_rates_sp_pub > 0) { - orb_publish(ORB_ID(vehicle_rates_setpoint), _v_rates_sp_pub, &_v_rates_sp); + if (_actuators_0_pub > 0) { + orb_publish(ORB_ID(actuator_controls_0), _actuators_0_pub, &_actuators); } else { - _v_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_v_rates_sp); + _actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators); } - } else { - /* attitude controller disabled */ - // TODO poll 'attitude_rates_setpoint' topic - _rates_sp.zero(); - _thrust_sp = 0.0f; - } + // FIX this: This is the atitude control logic for mc's - if (_v_control_mode.flag_control_rates_enabled) { - control_attitude_rates(dt); + if (_v_control_mode.flag_control_attitude_enabled) { + control_attitude(dt); - /* publish actuator controls */ - _actuators.control[0] = (isfinite(_att_control(0))) ? _att_control(0) : 0.0f; - _actuators.control[1] = (isfinite(_att_control(1))) ? _att_control(1) : 0.0f; - _actuators.control[2] = (isfinite(_att_control(2))) ? _att_control(2) : 0.0f; - _actuators.control[3] = (isfinite(_thrust_sp)) ? _thrust_sp : 0.0f; - _actuators.timestamp = hrt_absolute_time(); + /* publish attitude rates setpoint */ + _v_rates_sp.roll = _rates_sp(0); + _v_rates_sp.pitch = _rates_sp(1); + _v_rates_sp.yaw = _rates_sp(2); + _v_rates_sp.thrust = _thrust_sp; + _v_rates_sp.timestamp = hrt_absolute_time(); - if (_actuators_0_pub > 0) { - orb_publish(ORB_ID(actuator_controls_0), _actuators_0_pub, &_actuators); + if (_v_rates_sp_pub > 0) { + orb_publish(ORB_ID(vehicle_rates_setpoint), _v_rates_sp_pub, &_v_rates_sp); + + } else { + _v_rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &_v_rates_sp); + } } else { - _actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators); + /* attitude controller disabled */ + // TODO poll 'attitude_rates_setpoint' topic + _rates_sp.zero(); + _thrust_sp = 0.0f; + } + + if (_v_control_mode.flag_control_rates_enabled) { + control_attitude_rates(dt); + + /* publish actuator controls */ + _actuators.control[0] = (isfinite(_att_control(0))) ? _att_control(0) : 0.0f; + _actuators.control[1] = (isfinite(_att_control(1))) ? _att_control(1) : 0.0f; + _actuators.control[2] = (isfinite(_att_control(2))) ? _att_control(2) : 0.0f; + _actuators.control[3] = (isfinite(_thrust_sp)) ? _thrust_sp : 0.0f; + _actuators.timestamp = hrt_absolute_time(); + + if (_actuators_0_pub > 0) { + orb_publish(ORB_ID(actuator_controls_0), _actuators_0_pub, &_actuators); + + } else { + _actuators_0_pub = orb_advertise(ORB_ID(actuator_controls_0), &_actuators); + } } } } -- cgit v1.2.3 From faa7d9577d20d38741fe9accabb372f088b9dc6a Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Wed, 26 Feb 2014 11:27:42 +0000 Subject: commented out gcs_link = false; when receiving swarm messages, since we still want imu and atitude messages in offboard mode --- src/modules/mavlink/mavlink_receiver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 8ea0f9ea3..6c0eb169b 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -277,7 +277,7 @@ handle_message(mavlink_message_t *msg) if (mavlink_system.sysid < 4) { /* switch to a receiving link mode */ - gcs_link = false; +// gcs_link = false; // commented this because I wanted to still receive imu and attitude info when in offboard mode /* * rate control mode - defined by MAVLink -- cgit v1.2.3 From f4a6b07e293037d632f080da4ff7504ff97731f6 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Wed, 26 Feb 2014 11:29:31 +0000 Subject: indenting changes to make should_arm condition more readable --- src/modules/px4iofirmware/mixer.cpp | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 6a4429461..760ca2e27 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -173,15 +173,16 @@ mixer_tick(void) * here. */ should_arm = ( - /* IO initialised without error */ (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) - /* and IO is armed */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) - /* and FMU is armed */ && ( - ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) - /* and there is valid input via or mixer */ && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK) ) - /* or direct PWM is set */ || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM) - /* or failsafe was set manually */ || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK)) - ) - ); + (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK)/* IO initialised without error */ + && (r_status_flags & PX4IO_P_STATUS_FLAGS_SAFETY_OFF)/* and IO is armed */ + && ( + ((r_setup_arming & PX4IO_P_SETUP_ARMING_FMU_ARMED)/* and FMU is armed */ + && (r_status_flags & PX4IO_P_STATUS_FLAGS_MIXER_OK))/* and there is valid input via or mixer */ + || (r_status_flags & PX4IO_P_STATUS_FLAGS_RAW_PWM)/* or direct PWM is set */ + || ((r_setup_arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) + && !(r_status_flags & PX4IO_P_STATUS_FLAGS_FMU_OK))/* or failsafe was set manually */ + ) + ); should_always_enable_pwm = (r_setup_arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) && (r_status_flags & PX4IO_P_STATUS_FLAGS_INIT_OK) -- cgit v1.2.3 From 52b29cae39a93a0c5218e911e61d1f6cfe6115c1 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Wed, 26 Feb 2014 14:21:34 +0000 Subject: added poll to 'attitude_rates_setpoint' as requested in TODO --- src/examples/jetdrive_control/jetdrive_control_main.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/examples/jetdrive_control/jetdrive_control_main.cpp b/src/examples/jetdrive_control/jetdrive_control_main.cpp index d91f89401..409ccad63 100644 --- a/src/examples/jetdrive_control/jetdrive_control_main.cpp +++ b/src/examples/jetdrive_control/jetdrive_control_main.cpp @@ -596,8 +596,9 @@ JetdriveControl::task_main() } else { /* attitude controller disabled */ // TODO poll 'attitude_rates_setpoint' topic - _rates_sp.zero(); - _thrust_sp = 0.0f; + vehicle_rates_setpoint_poll(); +// _rates_sp.zero(); +// _thrust_sp = 0.0f; } if (_v_control_mode.flag_control_rates_enabled) { -- cgit v1.2.3 From 0656aae3cb46f405888d8130e9db4bb3f9dd529a Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Wed, 26 Feb 2014 14:31:23 +0000 Subject: Now setting flag_external_manual_override_ok to false when in offboard mode,so that fmu has control over outputs. Added handling of OFFBOARD_CONTROL_MODE_DIRECT_RATES. --- src/modules/commander/commander.cpp | 11 ++++++++++- src/modules/mavlink/mavlink_receiver.cpp | 18 ++++++++++++++++++ 2 files changed, 28 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index f0debef1c..5e242050b 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1728,8 +1728,17 @@ set_control_mode() control_mode.flag_control_climb_rate_enabled = false; control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; + control_mode.flag_external_manual_override_ok = false; + break; + case OFFBOARD_CONTROL_MODE_DIRECT_RATES: + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_position_enabled = false; + control_mode.flag_control_velocity_enabled = false; + control_mode.flag_external_manual_override_ok = false; break; - default: control_mode.flag_control_rates_enabled = false; control_mode.flag_control_attitude_enabled = false; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 6c0eb169b..ba886e29e 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -98,6 +98,7 @@ static struct vehicle_vicon_position_s vicon_position; static struct vehicle_command_s vcmd; static struct offboard_control_setpoint_s offboard_control_sp; static struct vehicle_attitude_setpoint_s att_sp; +static struct vehicle_rates_setpoint_s rates_sp; static struct vehicle_control_mode_s _v_control_mode; struct vehicle_global_position_s hil_global_pos; @@ -130,6 +131,7 @@ static orb_advert_t flow_pub = -1; static orb_advert_t offboard_control_sp_pub = -1; static orb_advert_t att_sp_pub = -1; +static orb_advert_t rates_sp_pub = -1; static orb_advert_t vicon_position_pub = -1; static orb_advert_t telemetry_status_pub = -1; @@ -343,6 +345,22 @@ handle_message(mavlink_message_t *msg) // if (v_status.main_state == MAIN_STATE_OFFBOARD) { /* in offboard mode also publish setpoint directly */ switch (offboard_control_sp.mode) { + case OFFBOARD_CONTROL_MODE_DIRECT_RATES: + rates_sp.timestamp = hrt_absolute_time(); + rates_sp.roll = offboard_control_sp.p1; + rates_sp.pitch = offboard_control_sp.p2; + rates_sp.yaw = offboard_control_sp.p3; + rates_sp.thrust = offboard_control_sp.p4; + + /* check if topic has to be advertised */ + if(rates_sp_pub <= 0) { + rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); + + } else { + /* publish */ + orb_publish(ORB_ID(vehicle_rates_setpoint), &rates_sp); + } + break; case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: att_sp.timestamp = hrt_absolute_time(); att_sp.roll_body = offboard_control_sp.p1; -- cgit v1.2.3 From be4af0ab3bd1b4313ba23cbe4c7e2702d56d3644 Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Wed, 26 Feb 2014 17:07:29 +0000 Subject: code clean up --- src/examples/jetdrive_control/jetdrive_control_main.cpp | 2 +- src/modules/commander/commander.cpp | 2 -- src/modules/mavlink/mavlink_receiver.cpp | 2 +- 3 files changed, 2 insertions(+), 4 deletions(-) diff --git a/src/examples/jetdrive_control/jetdrive_control_main.cpp b/src/examples/jetdrive_control/jetdrive_control_main.cpp index 409ccad63..01435f572 100644 --- a/src/examples/jetdrive_control/jetdrive_control_main.cpp +++ b/src/examples/jetdrive_control/jetdrive_control_main.cpp @@ -558,7 +558,7 @@ JetdriveControl::task_main() arming_status_poll(); vehicle_manual_poll(); - if(_v_control_mode.flag_external_manual_override_ok) + if(!_v_control_mode.flag_control_offboard_enabled) { /* manual/direct control */ _actuators.control[0] = _manual_control_sp .roll; diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 5e242050b..801ef8d01 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1728,7 +1728,6 @@ set_control_mode() control_mode.flag_control_climb_rate_enabled = false; control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; - control_mode.flag_external_manual_override_ok = false; break; case OFFBOARD_CONTROL_MODE_DIRECT_RATES: control_mode.flag_control_rates_enabled = true; @@ -1737,7 +1736,6 @@ set_control_mode() control_mode.flag_control_climb_rate_enabled = false; control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; - control_mode.flag_external_manual_override_ok = false; break; default: control_mode.flag_control_rates_enabled = false; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index ba886e29e..a834b2c3a 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -358,7 +358,7 @@ handle_message(mavlink_message_t *msg) } else { /* publish */ - orb_publish(ORB_ID(vehicle_rates_setpoint), &rates_sp); + orb_publish(ORB_ID(vehicle_rates_setpoint), rates_sp_pub, &rates_sp); } break; case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: -- cgit v1.2.3 From 0789189c0588ebebd24a523f9639411be89c6a9b Mon Sep 17 00:00:00 2001 From: Diogo Machado Date: Fri, 28 Feb 2014 16:24:15 +0000 Subject: - Added JC params to jetdrive control example app. - fixed offboard control mode rates --- .../jetdrive_control/jetdrive_control_main.cpp | 35 ++++++++++++++-------- .../jetdrive_control/jetdrive_control_params.c | 27 +++++++++-------- 2 files changed, 36 insertions(+), 26 deletions(-) diff --git a/src/examples/jetdrive_control/jetdrive_control_main.cpp b/src/examples/jetdrive_control/jetdrive_control_main.cpp index 01435f572..bb72f14e0 100644 --- a/src/examples/jetdrive_control/jetdrive_control_main.cpp +++ b/src/examples/jetdrive_control/jetdrive_control_main.cpp @@ -95,19 +95,19 @@ JetdriveControl::JetdriveControl() : I.identity(); - _params_handles.roll_p = param_find("MC_ROLL_P"); - _params_handles.roll_rate_p = param_find("MC_ROLLRATE_P"); - _params_handles.roll_rate_i = param_find("MC_ROLLRATE_I"); - _params_handles.roll_rate_d = param_find("MC_ROLLRATE_D"); - _params_handles.pitch_p = param_find("MC_PITCH_P"); - _params_handles.pitch_rate_p = param_find("MC_PITCHRATE_P"); - _params_handles.pitch_rate_i = param_find("MC_PITCHRATE_I"); - _params_handles.pitch_rate_d = param_find("MC_PITCHRATE_D"); - _params_handles.yaw_p = param_find("MC_YAW_P"); - _params_handles.yaw_rate_p = param_find("MC_YAWRATE_P"); - _params_handles.yaw_rate_i = param_find("MC_YAWRATE_I"); - _params_handles.yaw_rate_d = param_find("MC_YAWRATE_D"); - _params_handles.yaw_ff = param_find("MC_YAW_FF"); + _params_handles.roll_p = param_find("JC_ROLL_P"); + _params_handles.roll_rate_p = param_find("JC_ROLLRATE_P"); + _params_handles.roll_rate_i = param_find("JC_ROLLRATE_I"); + _params_handles.roll_rate_d = param_find("JC_ROLLRATE_D"); + _params_handles.pitch_p = param_find("JC_PITCH_P"); + _params_handles.pitch_rate_p = param_find("JC_PITCHRATE_P"); + _params_handles.pitch_rate_i = param_find("JC_PITCHRATE_I"); + _params_handles.pitch_rate_d = param_find("JC_PITCHRATE_D"); + _params_handles.yaw_p = param_find("JC_YAW_P"); + _params_handles.yaw_rate_p = param_find("JC_YAWRATE_P"); + _params_handles.yaw_rate_i = param_find("JC_YAWRATE_I"); + _params_handles.yaw_rate_d = param_find("JC_YAWRATE_D"); + _params_handles.yaw_ff = param_find("JC_YAW_FF"); _params_handles.rc_scale_yaw = param_find("RC_SCALE_YAW"); @@ -463,6 +463,11 @@ JetdriveControl::control_attitude_rates(float dt) /* angular rates error */ math::Vector<3> rates_err = _rates_sp - rates; + + // _att_control will be loaded to controls + // + // _att_control = (JC_XXXRATE_P * rates_err) + (JC_XXXRATE_D * (_rates_prev - rate) / dt) + _rates_int; + _att_control = _params.rate_p.emult(rates_err) + _params.rate_d.emult(_rates_prev - rates) / dt + _rates_int; _rates_prev = rates; @@ -597,6 +602,10 @@ JetdriveControl::task_main() /* attitude controller disabled */ // TODO poll 'attitude_rates_setpoint' topic vehicle_rates_setpoint_poll(); + _rates_sp(0) = _v_rates_sp.roll; + _rates_sp(1) = _v_rates_sp.pitch; + _rates_sp(2) = _v_rates_sp.yaw; + _thrust_sp = _v_rates_sp.thrust; // _rates_sp.zero(); // _thrust_sp = 0.0f; } diff --git a/src/examples/jetdrive_control/jetdrive_control_params.c b/src/examples/jetdrive_control/jetdrive_control_params.c index 27a45b6bb..14831ecf7 100644 --- a/src/examples/jetdrive_control/jetdrive_control_params.c +++ b/src/examples/jetdrive_control/jetdrive_control_params.c @@ -41,16 +41,17 @@ #include -PARAM_DEFINE_FLOAT(MC_ROLL_P, 6.0f); -PARAM_DEFINE_FLOAT(MC_ROLLRATE_P, 0.1f); -PARAM_DEFINE_FLOAT(MC_ROLLRATE_I, 0.0f); -PARAM_DEFINE_FLOAT(MC_ROLLRATE_D, 0.002f); -PARAM_DEFINE_FLOAT(MC_PITCH_P, 6.0f); -PARAM_DEFINE_FLOAT(MC_PITCHRATE_P, 0.1f); -PARAM_DEFINE_FLOAT(MC_PITCHRATE_I, 0.0f); -PARAM_DEFINE_FLOAT(MC_PITCHRATE_D, 0.002f); -PARAM_DEFINE_FLOAT(MC_YAW_P, 2.0f); -PARAM_DEFINE_FLOAT(MC_YAWRATE_P, 0.3f); -PARAM_DEFINE_FLOAT(MC_YAWRATE_I, 0.0f); -PARAM_DEFINE_FLOAT(MC_YAWRATE_D, 0.0f); -PARAM_DEFINE_FLOAT(MC_YAW_FF, 0.5f); + +PARAM_DEFINE_FLOAT(JC_ROLL_P, 6.0f); +PARAM_DEFINE_FLOAT(JC_ROLLRATE_P, 0.1f); +PARAM_DEFINE_FLOAT(JC_ROLLRATE_I, 0.0f); +PARAM_DEFINE_FLOAT(JC_ROLLRATE_D, 0.002f); +PARAM_DEFINE_FLOAT(JC_PITCH_P, 6.0f); +PARAM_DEFINE_FLOAT(JC_PITCHRATE_P, 0.1f); +PARAM_DEFINE_FLOAT(JC_PITCHRATE_I, 0.0f); +PARAM_DEFINE_FLOAT(JC_PITCHRATE_D, 0.002f); +PARAM_DEFINE_FLOAT(JC_YAW_P, 2.0f); +PARAM_DEFINE_FLOAT(JC_YAWRATE_P, 0.3f); +PARAM_DEFINE_FLOAT(JC_YAWRATE_I, 0.0f); +PARAM_DEFINE_FLOAT(JC_YAWRATE_D, 0.0f); +PARAM_DEFINE_FLOAT(JC_YAW_FF, 0.5f); -- cgit v1.2.3 From f4c36f8c5cf69bd3af55a1065ab7a18c999c054c Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 1 May 2014 20:57:36 +0200 Subject: mc_pos_control: use current velocity to calculate position setpoint on reset to make transition to stabilized modes more smooth --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 7c625a0c5..fe0e8fe1a 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -493,8 +493,8 @@ MulticopterPositionControl::reset_pos_sp() { if (_reset_pos_sp) { _reset_pos_sp = false; - _pos_sp(0) = _pos(0); - _pos_sp(1) = _pos(1); + _pos_sp(0) = _pos(0) + _vel(0) / _params.pos_p(0); + _pos_sp(1) = _pos(1) + _vel(1) / _params.pos_p(1); mavlink_log_info(_mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", (double)_pos_sp(0), (double)_pos_sp(1)); } } @@ -504,7 +504,7 @@ MulticopterPositionControl::reset_alt_sp() { if (_reset_alt_sp) { _reset_alt_sp = false; - _pos_sp(2) = _pos(2); + _pos_sp(2) = _pos(2) + _vel(2) / _params.pos_p(2); mavlink_log_info(_mavlink_fd, "[mpc] reset alt sp: %.2f", -(double)_pos_sp(2)); } } -- cgit v1.2.3 From 7232c0354bee1f8f572bdb2f53f9969ba9778a6e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 1 May 2014 23:01:30 +0200 Subject: mc_pos_control: use MPC_XXX_FF to adjust setpoint on reset --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index fe0e8fe1a..356f3c15e 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -388,9 +388,11 @@ MulticopterPositionControl::parameters_update(bool force) param_get(_params_handles.z_vel_max, &v); _params.vel_max(2) = v; param_get(_params_handles.xy_ff, &v); + v = math::constrain(v, 0.0f, 1.0f); _params.vel_ff(0) = v; _params.vel_ff(1) = v; param_get(_params_handles.z_ff, &v); + v = math::constrain(v, 0.0f, 1.0f); _params.vel_ff(2) = v; _params.sp_offs_max = _params.vel_max.edivide(_params.pos_p) * 2.0f; @@ -493,8 +495,8 @@ MulticopterPositionControl::reset_pos_sp() { if (_reset_pos_sp) { _reset_pos_sp = false; - _pos_sp(0) = _pos(0) + _vel(0) / _params.pos_p(0); - _pos_sp(1) = _pos(1) + _vel(1) / _params.pos_p(1); + _pos_sp(0) = _pos(0) + _vel(0) / _params.pos_p(0) * (1.0f - _params.vel_ff(0)); + _pos_sp(1) = _pos(1) + _vel(1) / _params.pos_p(1) * (1.0f - _params.vel_ff(1)); mavlink_log_info(_mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", (double)_pos_sp(0), (double)_pos_sp(1)); } } @@ -504,7 +506,7 @@ MulticopterPositionControl::reset_alt_sp() { if (_reset_alt_sp) { _reset_alt_sp = false; - _pos_sp(2) = _pos(2) + _vel(2) / _params.pos_p(2); + _pos_sp(2) = _pos(2) + _vel(2) / _params.pos_p(2) * (1.0f - _params.vel_ff(2)); mavlink_log_info(_mavlink_fd, "[mpc] reset alt sp: %.2f", -(double)_pos_sp(2)); } } -- cgit v1.2.3 From 7813566e6680f4940989fb91760ddb0782b05858 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 6 May 2014 19:30:45 +0400 Subject: Initial UAVCAN integration. The library compiles successfully, CAN driver appears to be working properly. There is one hardcoded path in the module makefile that needs to be fixed; plus the compilation will likely fail unless arch/math.h contains log2l() --- .gitignore | 1 + makefiles/config_px4fmu-v2_default.mk | 1 + makefiles/setup.mk | 1 + makefiles/toolchain_gnu-arm-eabi.mk | 2 +- src/modules/uavcan/.gitignore | 1 + src/modules/uavcan/module.mk | 74 +++++++++++++++++++++++++ src/modules/uavcan/uavcan_clock.cpp | 65 ++++++++++++++++++++++ src/modules/uavcan/uavcan_main.cpp | 100 ++++++++++++++++++++++++++++++++++ src/modules/uavcan/uavcan_main.hpp | 39 +++++++++++++ 9 files changed, 283 insertions(+), 1 deletion(-) create mode 100644 src/modules/uavcan/.gitignore create mode 100644 src/modules/uavcan/module.mk create mode 100644 src/modules/uavcan/uavcan_clock.cpp create mode 100644 src/modules/uavcan/uavcan_main.cpp create mode 100644 src/modules/uavcan/uavcan_main.hpp diff --git a/.gitignore b/.gitignore index 5b345b34a..8c3bb1bb5 100644 --- a/.gitignore +++ b/.gitignore @@ -37,3 +37,4 @@ mavlink/include/mavlink/v0.9/ tags .tags_sorted_by_file .pydevproject +/uavcan diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index e13421acc..09b5bf7c6 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -73,6 +73,7 @@ MODULES += modules/commander MODULES += modules/navigator MODULES += modules/mavlink MODULES += modules/gpio_led +MODULES += modules/uavcan # # Estimation modules (EKF/ SO3 / other filters) diff --git a/makefiles/setup.mk b/makefiles/setup.mk index 183b143d6..a5271c656 100644 --- a/makefiles/setup.mk +++ b/makefiles/setup.mk @@ -48,6 +48,7 @@ export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/ export NUTTX_SRC = $(abspath $(PX4_BASE)/NuttX/nuttx)/ export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/NuttX/apps)/ export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink)/ +export UAVCAN_DIR = $(abspath $(PX4_BASE)/uavcan)/ export ROMFS_SRC = $(abspath $(PX4_BASE)/ROMFS)/ export IMAGE_DIR = $(abspath $(PX4_BASE)/Images)/ export BUILD_DIR = $(abspath $(PX4_BASE)/Build)/ diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index b519e0e7a..3c00e77f1 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -111,7 +111,7 @@ INSTRUMENTATIONDEFINES = $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH)) # Language-specific flags # ARCHCFLAGS = -std=gnu99 -ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x +ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -fno-threadsafe-statics # Generic warnings # diff --git a/src/modules/uavcan/.gitignore b/src/modules/uavcan/.gitignore new file mode 100644 index 000000000..24fbf171f --- /dev/null +++ b/src/modules/uavcan/.gitignore @@ -0,0 +1 @@ +./dsdlc_generated/ diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk new file mode 100644 index 000000000..5caa8d401 --- /dev/null +++ b/src/modules/uavcan/module.mk @@ -0,0 +1,74 @@ +############################################################################ +# +# Copyright (C) 2013 PX4 Development Team. All rights reserved. +# Author: Pavel Kirienko +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# UAVCAN <--> uORB bridge +# + +MODULE_COMMAND = uavcan + +MAXOPTIMIZATION = -Os + +SRCS += uavcan_main.cpp \ + uavcan_clock.cpp + +# +# libuavcan +# +include $(UAVCAN_DIR)/libuavcan/include.mk +SRCS += $(LIBUAVCAN_SRC) +# TODO fix include path +INCLUDE_DIRS += $(LIBUAVCAN_INC) /media/storage/px4/Firmware/Build/px4fmu-v2_default.build/nuttx-export/include/cxx/ +EXTRADEFINES += -DUAVCAN_MEM_POOL_BLOCK_SIZE=56 \ + -DUAVCAN_TOSTRING=0 \ + -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 \ + -DUAVCAN_IMPLEMENT_PLACEMENT_NEW=1 + +# +# libuavcan drivers for STM32 +# +include $(UAVCAN_DIR)/libuavcan_drivers/stm32/driver/include.mk +SRCS += $(LIBUAVCAN_STM32_SRC) +INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC) +EXTRADEFINES += -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=1 + +# +# Invoke DSDL compiler +# TODO: Add make target for this, or invoke dsdlc manually. +# The second option assumes that the generated headers shall be saved +# under the version control, which may be undesirable. +# The first option requires python3 and python3-mako for the sources to be built. +# +$(info $(shell $(LIBUAVCAN_DSDLC) $(UAVCAN_DSDL_DIR))) +INCLUDE_DIRS += dsdlc_generated diff --git a/src/modules/uavcan/uavcan_clock.cpp b/src/modules/uavcan/uavcan_clock.cpp new file mode 100644 index 000000000..2a5e88989 --- /dev/null +++ b/src/modules/uavcan/uavcan_clock.cpp @@ -0,0 +1,65 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * Author: Pavel Kirienko + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include + +namespace uavcan_stm32 +{ +namespace clock +{ + +uavcan::MonotonicTime getMonotonic() +{ + return uavcan::MonotonicTime::fromUSec(hrt_absolute_time()); +} + +uavcan::UtcTime getUtc() +{ + return uavcan::UtcTime(); +} + +void adjustUtc(uavcan::UtcDuration adjustment) +{ + (void)adjustment; +} + +uavcan::uint64_t getUtcUSecFromCanInterrupt() +{ + return 0; +} + +} +} + diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp new file mode 100644 index 000000000..fbb2e174b --- /dev/null +++ b/src/modules/uavcan/uavcan_main.cpp @@ -0,0 +1,100 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * Author: Pavel Kirienko + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#include +#include +#include +#include +#include +#include "uavcan_main.hpp" + +extern "C" __EXPORT int uavcan_main(int argc, char *argv[]); + +namespace +{ + +uavcan_stm32::CanInitHelper<> can_driver; + +void print_usage() +{ + warnx("usage: uavcan start [can_bitrate]"); +} + +int test_thread(int argc, char *argv[]) +{ + stm32_configgpio(GPIO_CAN1_RX); + stm32_configgpio(GPIO_CAN1_TX); + stm32_configgpio(GPIO_CAN2_RX); + stm32_configgpio(GPIO_CAN2_TX); + int res = can_driver.init(1000000); + if (res < 0) + { + errx(res, "CAN driver init failed"); + } + while (true) + { + ::sleep(1); + auto iface = static_cast(can_driver.driver.getIface(0)); + res = iface->send(uavcan::CanFrame(), uavcan_stm32::clock::getMonotonic(), 0); + warnx("published %i, pending %u", res, can_driver.driver.getIface(0)->getRxQueueLength()); + } + return 0; +} + +} + +int uavcan_main(int argc, char *argv[]) +{ + if (argc < 2) { + print_usage(); + ::exit(1); + } + + if (!std::strcmp(argv[1], "start")) { + static bool started = false; + if (started) + { + warnx("already started"); + ::exit(1); + } + started = true; + (void)task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 3000, + static_cast(&test_thread), const_cast(argv)); + return 0; + } else { + print_usage(); + ::exit(1); + } + return 0; +} diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp new file mode 100644 index 000000000..7fcc992d0 --- /dev/null +++ b/src/modules/uavcan/uavcan_main.hpp @@ -0,0 +1,39 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * Author: Pavel Kirienko + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +#pragma once + +#include + +// ... -- cgit v1.2.3 From 7d7a375dd1a69bd286f127de51b11e5ecd390640 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 6 May 2014 19:42:40 +0400 Subject: Fixed hardcoded include path --- makefiles/nuttx.mk | 1 + src/modules/uavcan/module.mk | 6 +++--- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/makefiles/nuttx.mk b/makefiles/nuttx.mk index d283096b2..bf0744140 100644 --- a/makefiles/nuttx.mk +++ b/makefiles/nuttx.mk @@ -64,6 +64,7 @@ LDSCRIPT += $(NUTTX_EXPORT_DIR)build/ld.script # Add directories from the NuttX export to the relevant search paths # INCLUDE_DIRS += $(NUTTX_EXPORT_DIR)include \ + $(NUTTX_EXPORT_DIR)include/cxx \ $(NUTTX_EXPORT_DIR)arch/chip \ $(NUTTX_EXPORT_DIR)arch/common diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index 5caa8d401..6974de8ca 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -48,8 +48,7 @@ SRCS += uavcan_main.cpp \ # include $(UAVCAN_DIR)/libuavcan/include.mk SRCS += $(LIBUAVCAN_SRC) -# TODO fix include path -INCLUDE_DIRS += $(LIBUAVCAN_INC) /media/storage/px4/Firmware/Build/px4fmu-v2_default.build/nuttx-export/include/cxx/ +INCLUDE_DIRS += $(LIBUAVCAN_INC) EXTRADEFINES += -DUAVCAN_MEM_POOL_BLOCK_SIZE=56 \ -DUAVCAN_TOSTRING=0 \ -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 \ @@ -61,7 +60,8 @@ EXTRADEFINES += -DUAVCAN_MEM_POOL_BLOCK_SIZE=56 \ include $(UAVCAN_DIR)/libuavcan_drivers/stm32/driver/include.mk SRCS += $(LIBUAVCAN_STM32_SRC) INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC) -EXTRADEFINES += -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=1 +EXTRADEFINES += -DUAVCAN_STM32_NUTTX \ + -DUAVCAN_STM32_NUM_IFACES=1 # # Invoke DSDL compiler -- cgit v1.2.3 From 5716dad25db27315fa7cebf8183a71f864860f41 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 6 May 2014 20:14:07 +0400 Subject: Added workaround for hardware issue on Pixhawk v1 --- src/modules/uavcan/module.mk | 2 +- src/modules/uavcan/uavcan_main.cpp | 8 +++++++- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index 6974de8ca..3966210b5 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -61,7 +61,7 @@ include $(UAVCAN_DIR)/libuavcan_drivers/stm32/driver/include.mk SRCS += $(LIBUAVCAN_STM32_SRC) INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC) EXTRADEFINES += -DUAVCAN_STM32_NUTTX \ - -DUAVCAN_STM32_NUM_IFACES=1 + -DUAVCAN_STM32_NUM_IFACES=2 # # Invoke DSDL compiler diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index fbb2e174b..474063aa6 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -37,6 +37,7 @@ #include #include #include +#include #include "uavcan_main.hpp" extern "C" __EXPORT int uavcan_main(int argc, char *argv[]); @@ -53,9 +54,14 @@ void print_usage() int test_thread(int argc, char *argv[]) { + /* + * Forced pull up on CAN2 is required for Pixhawk v1 where the second interface lacks a transceiver. + * If no transceiver is connected, the RX pin will float, occasionally causing CAN controller to + * fail during initialization. + */ stm32_configgpio(GPIO_CAN1_RX); stm32_configgpio(GPIO_CAN1_TX); - stm32_configgpio(GPIO_CAN2_RX); + stm32_configgpio(GPIO_CAN2_RX | GPIO_PULLUP); stm32_configgpio(GPIO_CAN2_TX); int res = can_driver.init(1000000); if (res < 0) -- cgit v1.2.3 From 4b11145797fdc26e5bf29738dd319ab9e8003356 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Wed, 7 May 2014 13:42:34 +0400 Subject: Working UAVCAN node. No application logic is implemented yet; the node just publishes its status once a second (uavcan.protocol.NodeStatus) and responds to basic services (transport stats, node discovery) --- src/modules/uavcan/uavcan_clock.cpp | 7 ++ src/modules/uavcan/uavcan_main.cpp | 149 ++++++++++++++++++++++++++++-------- src/modules/uavcan/uavcan_main.hpp | 29 ++++++- 3 files changed, 151 insertions(+), 34 deletions(-) diff --git a/src/modules/uavcan/uavcan_clock.cpp b/src/modules/uavcan/uavcan_clock.cpp index 2a5e88989..0e844f346 100644 --- a/src/modules/uavcan/uavcan_clock.cpp +++ b/src/modules/uavcan/uavcan_clock.cpp @@ -60,6 +60,13 @@ uavcan::uint64_t getUtcUSecFromCanInterrupt() return 0; } +} // namespace clock + +SystemClock& SystemClock::instance() +{ + static SystemClock inst; + return inst; } + } diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 474063aa6..bf6d4fb08 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -40,64 +40,147 @@ #include #include "uavcan_main.hpp" -extern "C" __EXPORT int uavcan_main(int argc, char *argv[]); +/* + * UavcanNode + */ +UavcanNode* UavcanNode::_instance; -namespace +int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) { + if (_instance != nullptr) { + warnx("Already started"); + return -1; + } -uavcan_stm32::CanInitHelper<> can_driver; - -void print_usage() -{ - warnx("usage: uavcan start [can_bitrate]"); -} - -int test_thread(int argc, char *argv[]) -{ /* + * GPIO config. * Forced pull up on CAN2 is required for Pixhawk v1 where the second interface lacks a transceiver. * If no transceiver is connected, the RX pin will float, occasionally causing CAN controller to * fail during initialization. */ - stm32_configgpio(GPIO_CAN1_RX); - stm32_configgpio(GPIO_CAN1_TX); + stm32_configgpio (GPIO_CAN1_RX); + stm32_configgpio (GPIO_CAN1_TX); stm32_configgpio(GPIO_CAN2_RX | GPIO_PULLUP); - stm32_configgpio(GPIO_CAN2_TX); - int res = can_driver.init(1000000); - if (res < 0) - { - errx(res, "CAN driver init failed"); + stm32_configgpio (GPIO_CAN2_TX); + + /* + * CAN driver init + */ + static CanInitHelper can; + static bool can_initialized = false; + if (!can_initialized) { + const int can_init_res = can.init(bitrate); + if (can_init_res < 0) { + warnx("CAN driver init failed %i", can_init_res); + return can_init_res; + } + can_initialized = true; } - while (true) - { - ::sleep(1); - auto iface = static_cast(can_driver.driver.getIface(0)); - res = iface->send(uavcan::CanFrame(), uavcan_stm32::clock::getMonotonic(), 0); - warnx("published %i, pending %u", res, can_driver.driver.getIface(0)->getRxQueueLength()); + + /* + * Node init + */ + _instance = new UavcanNode(can.driver, uavcan_stm32::SystemClock::instance()); + if (_instance == nullptr) { + warnx("Out of memory"); + return -1; } - return 0; + const int node_init_res = _instance->init(node_id); + if (node_init_res < 0) { + delete _instance; + _instance = nullptr; + warnx("Node init failed %i", node_init_res); + return node_init_res; + } + + /* + * Start the task. Normally it should never exit. + */ + static auto run_trampoline = [](int, char*[]) {return UavcanNode::_instance->run();}; + return task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, StackSize, + static_cast(run_trampoline), nullptr); } +int UavcanNode::init(uavcan::NodeID node_id) +{ + uavcan::protocol::SoftwareVersion swver; + swver.major = 12; // TODO fill version info + swver.minor = 34; + _node.setSoftwareVersion(swver); + + uavcan::protocol::HardwareVersion hwver; + hwver.major = 42; // TODO fill version info + hwver.minor = 42; + _node.setHardwareVersion(hwver); + + _node.setName("org.pixhawk"); // Huh? + + _node.setNodeID(node_id); + + return _node.start(); +} + +int UavcanNode::run() +{ + _node.setStatusOk(); + while (true) { + // TODO: ORB multiplexing + const int res = _node.spin(uavcan::MonotonicDuration::getInfinite()); + if (res < 0) { + warnx("Spin error %i", res); + ::sleep(1); + } + } + return -1; } +/* + * App entry point + */ +static void print_usage() +{ + warnx("usage: uavcan start [can_bitrate]"); +} + +extern "C" __EXPORT int uavcan_main(int argc, char *argv[]); + int uavcan_main(int argc, char *argv[]) { + constexpr long DEFAULT_CAN_BITRATE = 1000000; + if (argc < 2) { print_usage(); ::exit(1); } if (!std::strcmp(argv[1], "start")) { - static bool started = false; - if (started) - { - warnx("already started"); + if (argc < 3) { + print_usage(); ::exit(1); } - started = true; - (void)task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, 3000, - static_cast(&test_thread), const_cast(argv)); - return 0; + /* + * Node ID + */ + const int node_id = atoi(argv[2]); + if (node_id < 0 || node_id > uavcan::NodeID::Max || !uavcan::NodeID(node_id).isUnicast()) { + warnx("Invalid Node ID %i", node_id); + ::exit(1); + } + /* + * CAN bitrate + */ + long bitrate = 0; + if (argc > 3) { + bitrate = atol(argv[3]); + } + if (bitrate <= 0) { + bitrate = DEFAULT_CAN_BITRATE; + } + /* + * Start + */ + warnx("Node ID %i, bitrate %li", node_id, bitrate); + return UavcanNode::start(node_id, bitrate); } else { print_usage(); ::exit(1); diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 7fcc992d0..8bd660cc5 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -36,4 +36,31 @@ #include -// ... +/** + * Implements basic functinality of UAVCAN node. + */ +class UavcanNode +{ + static constexpr unsigned MemPoolSize = 10752; + static constexpr unsigned RxQueueLenPerIface = 64; + static constexpr unsigned StackSize = 3000; + +public: + typedef uavcan::Node Node; + typedef uavcan_stm32::CanInitHelper CanInitHelper; + + UavcanNode(uavcan::ICanDriver& can_driver, uavcan::ISystemClock& system_clock) + : _node(can_driver, system_clock) + { } + + static int start(uavcan::NodeID node_id, uint32_t bitrate); + + Node& getNode() { return _node; } + +private: + int init(uavcan::NodeID node_id); + int run(); + + static UavcanNode* _instance; + Node _node; +}; -- cgit v1.2.3 From 04df4270f0ac6aec360076185363338366475166 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Wed, 7 May 2014 13:56:05 +0400 Subject: Removed the placement new workaround. It seems like we can pull from the toolchain's standard includes with no harm. --- src/modules/uavcan/module.mk | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index 3966210b5..c91208342 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -51,8 +51,7 @@ SRCS += $(LIBUAVCAN_SRC) INCLUDE_DIRS += $(LIBUAVCAN_INC) EXTRADEFINES += -DUAVCAN_MEM_POOL_BLOCK_SIZE=56 \ -DUAVCAN_TOSTRING=0 \ - -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 \ - -DUAVCAN_IMPLEMENT_PLACEMENT_NEW=1 + -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 # # libuavcan drivers for STM32 -- cgit v1.2.3 From be728d189e4b1b04de5a0b45710e08effcf50b8b Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Wed, 7 May 2014 14:24:40 +0400 Subject: Catching up with libuavcan - some preprocessor symbols are no longer required to be defined explicitly --- src/modules/uavcan/module.mk | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index c91208342..098543879 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -49,9 +49,9 @@ SRCS += uavcan_main.cpp \ include $(UAVCAN_DIR)/libuavcan/include.mk SRCS += $(LIBUAVCAN_SRC) INCLUDE_DIRS += $(LIBUAVCAN_INC) -EXTRADEFINES += -DUAVCAN_MEM_POOL_BLOCK_SIZE=56 \ - -DUAVCAN_TOSTRING=0 \ - -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 +# Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile +# because this platform lacks most of the standard library and STL. Hence we need to force C++03 mode. +EXTRADEFINES += -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 # # libuavcan drivers for STM32 -- cgit v1.2.3 From 973b193261fab69320f25fae68345a60d7678dc8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 7 May 2014 14:29:30 +0200 Subject: Fixed comments and code style of UAVCAN node --- src/modules/uavcan/uavcan_clock.cpp | 13 +++++++++--- src/modules/uavcan/uavcan_main.cpp | 40 +++++++++++++++++++++++++++++-------- src/modules/uavcan/uavcan_main.hpp | 19 ++++++++++++------ 3 files changed, 55 insertions(+), 17 deletions(-) diff --git a/src/modules/uavcan/uavcan_clock.cpp b/src/modules/uavcan/uavcan_clock.cpp index 0e844f346..e41d5f953 100644 --- a/src/modules/uavcan/uavcan_clock.cpp +++ b/src/modules/uavcan/uavcan_clock.cpp @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2014 PX4 Development Team. All rights reserved. - * Author: Pavel Kirienko + * Copyright (c) 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -35,6 +34,14 @@ #include #include +/** + * @file uavcan_clock.cpp + * + * Implements a clock for the CAN node. + * + * @author Pavel Kirienko + */ + namespace uavcan_stm32 { namespace clock @@ -62,7 +69,7 @@ uavcan::uint64_t getUtcUSecFromCanInterrupt() } // namespace clock -SystemClock& SystemClock::instance() +SystemClock &SystemClock::instance() { static SystemClock inst; return inst; diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index bf6d4fb08..8d715e3b1 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2014 PX4 Development Team. All rights reserved. - * Author: Pavel Kirienko + * Copyright (c) 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -40,10 +39,18 @@ #include #include "uavcan_main.hpp" +/** + * @file uavcan_main.cpp + * + * Implements basic functinality of UAVCAN node. + * + * @author Pavel Kirienko + */ + /* * UavcanNode */ -UavcanNode* UavcanNode::_instance; +UavcanNode *UavcanNode::_instance; int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) { @@ -58,22 +65,25 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) * If no transceiver is connected, the RX pin will float, occasionally causing CAN controller to * fail during initialization. */ - stm32_configgpio (GPIO_CAN1_RX); - stm32_configgpio (GPIO_CAN1_TX); + stm32_configgpio(GPIO_CAN1_RX); + stm32_configgpio(GPIO_CAN1_TX); stm32_configgpio(GPIO_CAN2_RX | GPIO_PULLUP); - stm32_configgpio (GPIO_CAN2_TX); + stm32_configgpio(GPIO_CAN2_TX); /* * CAN driver init */ static CanInitHelper can; static bool can_initialized = false; + if (!can_initialized) { const int can_init_res = can.init(bitrate); + if (can_init_res < 0) { warnx("CAN driver init failed %i", can_init_res); return can_init_res; } + can_initialized = true; } @@ -81,11 +91,14 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) * Node init */ _instance = new UavcanNode(can.driver, uavcan_stm32::SystemClock::instance()); + if (_instance == nullptr) { warnx("Out of memory"); return -1; } + const int node_init_res = _instance->init(node_id); + if (node_init_res < 0) { delete _instance; _instance = nullptr; @@ -96,9 +109,9 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) /* * Start the task. Normally it should never exit. */ - static auto run_trampoline = [](int, char*[]) {return UavcanNode::_instance->run();}; + static auto run_trampoline = [](int, char *[]) {return UavcanNode::_instance->run();}; return task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, StackSize, - static_cast(run_trampoline), nullptr); + static_cast(run_trampoline), nullptr); } int UavcanNode::init(uavcan::NodeID node_id) @@ -123,14 +136,17 @@ int UavcanNode::init(uavcan::NodeID node_id) int UavcanNode::run() { _node.setStatusOk(); + while (true) { // TODO: ORB multiplexing const int res = _node.spin(uavcan::MonotonicDuration::getInfinite()); + if (res < 0) { warnx("Spin error %i", res); ::sleep(1); } } + return -1; } @@ -158,32 +174,40 @@ int uavcan_main(int argc, char *argv[]) print_usage(); ::exit(1); } + /* * Node ID */ const int node_id = atoi(argv[2]); + if (node_id < 0 || node_id > uavcan::NodeID::Max || !uavcan::NodeID(node_id).isUnicast()) { warnx("Invalid Node ID %i", node_id); ::exit(1); } + /* * CAN bitrate */ long bitrate = 0; + if (argc > 3) { bitrate = atol(argv[3]); } + if (bitrate <= 0) { bitrate = DEFAULT_CAN_BITRATE; } + /* * Start */ warnx("Node ID %i, bitrate %li", node_id, bitrate); return UavcanNode::start(node_id, bitrate); + } else { print_usage(); ::exit(1); } + return 0; } diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 8bd660cc5..b27449f1f 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2014 PX4 Development Team. All rights reserved. - * Author: Pavel Kirienko + * Copyright (c) 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -37,7 +36,15 @@ #include /** - * Implements basic functinality of UAVCAN node. + * @file uavcan_main.hpp + * + * Defines basic functinality of UAVCAN node. + * + * @author Pavel Kirienko + */ + +/** + * A UAVCAN node. */ class UavcanNode { @@ -49,18 +56,18 @@ public: typedef uavcan::Node Node; typedef uavcan_stm32::CanInitHelper CanInitHelper; - UavcanNode(uavcan::ICanDriver& can_driver, uavcan::ISystemClock& system_clock) + UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) : _node(can_driver, system_clock) { } static int start(uavcan::NodeID node_id, uint32_t bitrate); - Node& getNode() { return _node; } + Node &getNode() { return _node; } private: int init(uavcan::NodeID node_id); int run(); - static UavcanNode* _instance; + static UavcanNode *_instance; ///< pointer to the library instance Node _node; }; -- cgit v1.2.3 From ab5e76e3d9da5a76d6520e166d5370c6bdfc4a53 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 7 May 2014 15:03:08 +0200 Subject: Fixed printing of bit rate --- src/modules/uavcan/uavcan_main.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 8d715e3b1..ca4da1c2d 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -162,7 +162,7 @@ extern "C" __EXPORT int uavcan_main(int argc, char *argv[]); int uavcan_main(int argc, char *argv[]) { - constexpr long DEFAULT_CAN_BITRATE = 1000000; + constexpr unsigned DEFAULT_CAN_BITRATE = 1000000; if (argc < 2) { print_usage(); @@ -188,7 +188,7 @@ int uavcan_main(int argc, char *argv[]) /* * CAN bitrate */ - long bitrate = 0; + unsigned bitrate = 0; if (argc > 3) { bitrate = atol(argv[3]); @@ -201,7 +201,7 @@ int uavcan_main(int argc, char *argv[]) /* * Start */ - warnx("Node ID %i, bitrate %li", node_id, bitrate); + warnx("Node ID %u, bitrate %u", node_id, bitrate); return UavcanNode::start(node_id, bitrate); } else { -- cgit v1.2.3 From d62f3b8aa7a1ba932b932b26068b79bd14e205dd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 8 May 2014 09:14:23 +0200 Subject: Added mixing code, not complete, not compiliing --- src/modules/uavcan/uavcan_main.cpp | 254 ++++++++++++++++++++++++++++++++++++- src/modules/uavcan/uavcan_main.hpp | 27 +++- 2 files changed, 273 insertions(+), 8 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index ca4da1c2d..94fb15544 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -37,6 +37,9 @@ #include #include #include + +#include + #include "uavcan_main.hpp" /** @@ -52,6 +55,20 @@ */ UavcanNode *UavcanNode::_instance; +UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) : + _node(can_driver, system_clock), + _controls({}), + _poll_fds({}) +{ + _control_topics[0] = ORB_ID(actuator_controls_0); + _control_topics[1] = ORB_ID(actuator_controls_1); + _control_topics[2] = ORB_ID(actuator_controls_2); + _control_topics[3] = ORB_ID(actuator_controls_3); + + memset(_controls, 0, sizeof(_controls)); + memset(_poll_fds, 0, sizeof(_poll_fds)); +} + int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) { if (_instance != nullptr) { @@ -106,6 +123,14 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) return node_init_res; } + int ret; + + /* do regular cdev init */ + ret = CDev::init(); + + if (ret != OK) + return ret; + /* * Start the task. Normally it should never exit. */ @@ -137,8 +162,94 @@ int UavcanNode::run() { _node.setStatusOk(); + _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); + while (true) { - // TODO: ORB multiplexing + + if (_groups_subscribed != _groups_required) { + subscribe(); + _groups_subscribed = _groups_required; + /* force setting update rate */ + _current_update_rate = 0; + } + + int ret = ::poll(_poll_fds, _poll_fds_num, 5/* 5 ms wait time */); + + /* this would be bad... */ + if (ret < 0) { + log("poll error %d", errno); + usleep(1000000); + continue; + + } else if (ret == 0) { + /* timeout: no control data, switch to failsafe values */ +// warnx("no PWM: failsafe"); + + } else { + + /* get controls for required topics */ + unsigned poll_id = 0; + for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { + if (_control_subs[i] > 0) { + if (_poll_fds[poll_id].revents & POLLIN) { + orb_copy(_control_topics[i], _control_subs[i], &_controls[i]); + } + poll_id++; + } + } + + /* can we mix? */ + if (_mixers != nullptr) { + + // XXX one output group has 8 outputs max, + // but this driver could well serve multiple groups. + unsigned num_outputs_max = 8; + + // Do mixing + outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs_max); + outputs.timestamp = hrt_absolute_time(); + + /* iterate actuators */ + for (unsigned i = 0; i < outputs.noutputs; i++) { + /* last resort: catch NaN, INF and out-of-band errors */ + if (!isfinite(outputs.output[i]) || + outputs.output[i] < -1.0f || + outputs.output[i] > 1.0f) { + /* + * Value is NaN, INF or out of band - set to the minimum value. + * This will be clearly visible on the servo status and will limit the risk of accidentally + * spinning motors. It would be deadly in flight. + */ + outputs.output[i] = -1.0f; + } + } + + printf("CAN out: ") + /* output to the bus */ + for (unsigned i = 0; i < outputs.noutputs; i++) { + printf("%u: %8.4f ", i, outputs.output[i]) + // can_send_xxx + } + printf("\n"); + + } + } + + /* check arming state */ + bool updated = false; + orb_check(_armed_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); + + /* update the armed status and check that we're not locked down */ + bool set_armed = _armed.armed && !_armed.lockdown; + + arm_actuators(set_armed); + } + + // Output commands and fetch data + const int res = _node.spin(uavcan::MonotonicDuration::getInfinite()); if (res < 0) { @@ -147,7 +258,146 @@ int UavcanNode::run() } } - return -1; + teardown(); + + exit(0); +} + +int +UavcanNode::control_callback(uintptr_t handle, + uint8_t control_group, + uint8_t control_index, + float &input) +{ + const actuator_controls_s *controls = (actuator_controls_s *)handle; + + input = _controls[control_group].control[control_index]; + return 0; +} + +int +UavcanNode::teardown() +{ + for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { + if (_control_subs > 0) { + ::close(_control_subs[i]); + _control_subs[i] = -1; + } + } + ::close(_armed_sub); +} + +void +UavcanNode::arm_actuators(bool arm) +{ + bool changed = (_armed != arm); + + _armed = arm; + + if (changed) { + // Propagate immediately to CAN bus + } +} + +void +UavcanNode::subscribe() +{ + /* subscribe/unsubscribe to required actuator control groups */ + uint32_t sub_groups = _groups_required & ~_groups_subscribed; + uint32_t unsub_groups = _groups_subscribed & ~_groups_required; + _poll_fds_num = 0; + for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { + if (sub_groups & (1 << i)) { + warnx("subscribe to actuator_controls_%d", i); + _control_subs[i] = orb_subscribe(_control_topics[i]); + } + if (unsub_groups & (1 << i)) { + warnx("unsubscribe from actuator_controls_%d", i); + ::close(_control_subs[i]); + _control_subs[i] = -1; + } + + if (_control_subs[i] > 0) { + _poll_fds[_poll_fds_num].fd = _control_subs[i]; + _poll_fds[_poll_fds_num].events = POLLIN; + _poll_fds_num++; + } + } +} + +int +PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) +{ + int ret = OK; + + lock(); + + switch (cmd) { + case PWM_SERVO_ARM: + arm_actuators(true); + break; + + case PWM_SERVO_SET_ARM_OK: + case PWM_SERVO_CLEAR_ARM_OK: + case PWM_SERVO_SET_FORCE_SAFETY_OFF: + // these are no-ops, as no safety switch + break; + + case PWM_SERVO_DISARM: + arm_actuators(false); + break; + + case MIXERIOCGETOUTPUTCOUNT: + *(unsigned *)arg = _output_count; + break; + + case MIXERIOCRESET: + if (_mixers != nullptr) { + delete _mixers; + _mixers = nullptr; + _groups_required = 0; + } + + break; + + case MIXERIOCLOADBUF: { + const char *buf = (const char *)arg; + unsigned buflen = strnlen(buf, 1024); + + if (_mixers == nullptr) + _mixers = new MixerGroup(control_callback, (uintptr_t)_controls); + + if (_mixers == nullptr) { + _groups_required = 0; + ret = -ENOMEM; + + } else { + + ret = _mixers->load_from_buf(buf, buflen); + + if (ret != 0) { + debug("mixer load failed with %d", ret); + delete _mixers; + _mixers = nullptr; + _groups_required = 0; + ret = -EINVAL; + } else { + + _mixers->groups_required(_groups_required); + } + } + + break; + } + + default: + ret = -ENOTTY; + break; + } + + unlock(); + + return ret; } /* diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index b27449f1f..213cb4206 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -34,6 +34,7 @@ #pragma once #include +#include /** * @file uavcan_main.hpp @@ -46,7 +47,7 @@ /** * A UAVCAN node. */ -class UavcanNode +class UavcanNode : public device::CDev { static constexpr unsigned MemPoolSize = 10752; static constexpr unsigned RxQueueLenPerIface = 64; @@ -56,18 +57,32 @@ public: typedef uavcan::Node Node; typedef uavcan_stm32::CanInitHelper CanInitHelper; - UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) - : _node(can_driver, system_clock) - { } + UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock); static int start(uavcan::NodeID node_id, uint32_t bitrate); Node &getNode() { return _node; } + static int control_callback(uintptr_t handle, + uint8_t control_group, + uint8_t control_index, + float &input); + void subscribe(); + private: int init(uavcan::NodeID node_id); int run(); - static UavcanNode *_instance; ///< pointer to the library instance - Node _node; + static UavcanNode *_instance; ///< pointer to the library instance + Node _node; + + MixerGroup *_mixers; + + uint32_t _groups_required; + uint32_t _groups_subscribed; + int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS]; + actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS]; + orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS]; + pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS]; + unsigned _poll_fds_num; }; -- cgit v1.2.3 From 517f2df0d1de008c795061badc57fbfdbb68d0d5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 8 May 2014 13:28:41 +0200 Subject: UAVCAN: Fixed all compile errors --- src/modules/uavcan/uavcan_main.cpp | 124 ++++++++++++++++++++++++++----------- src/modules/uavcan/uavcan_main.hpp | 46 ++++++++++---- 2 files changed, 123 insertions(+), 47 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 94fb15544..332c3a5e8 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -31,14 +31,18 @@ * ****************************************************************************/ +#include + #include #include #include #include +#include #include #include -#include +#include +#include #include "uavcan_main.hpp" @@ -55,7 +59,13 @@ */ UavcanNode *UavcanNode::_instance; -UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) : +UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) : + CDev("uavcan", UAVCAN_DEVICE_PATH), + _task(0), + _task_should_exit(false), + _armed_sub(-1), + _is_armed(false), + _output_count(0), _node(can_driver, system_clock), _controls({}), _poll_fds({}) @@ -65,8 +75,37 @@ UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) : _control_topics[2] = ORB_ID(actuator_controls_2); _control_topics[3] = ORB_ID(actuator_controls_3); - memset(_controls, 0, sizeof(_controls)); - memset(_poll_fds, 0, sizeof(_poll_fds)); + // memset(_controls, 0, sizeof(_controls)); + // memset(_poll_fds, 0, sizeof(_poll_fds)); +} + +UavcanNode::~UavcanNode() +{ + if (_task != -1) { + /* tell the task we want it to go away */ + _task_should_exit = true; + + unsigned i = 10; + + do { + /* wait 50ms - it should wake every 100ms or so worst-case */ + usleep(50000); + + /* if we have given up, kill it */ + if (--i == 0) { + task_delete(_task); + break; + } + + } while (_task != -1); + } + + /* clean up the alternate device node */ + // unregister_driver(PWM_OUTPUT_DEVICE_PATH); + + ::close(_armed_sub); + + _instance = nullptr; } int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) @@ -123,24 +162,32 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) return node_init_res; } - int ret; - - /* do regular cdev init */ - ret = CDev::init(); - - if (ret != OK) - return ret; - /* * Start the task. Normally it should never exit. */ static auto run_trampoline = [](int, char *[]) {return UavcanNode::_instance->run();}; - return task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, StackSize, + _instance->_task = task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, StackSize, static_cast(run_trampoline), nullptr); + + if (_instance->_task < 0) { + warnx("start failed: %d", errno); + return -errno; + } + + return OK; } int UavcanNode::init(uavcan::NodeID node_id) { + + int ret; + + /* do regular cdev init */ + ret = CDev::init(); + + if (ret != OK) + return ret; + uavcan::protocol::SoftwareVersion swver; swver.major = 12; // TODO fill version info swver.minor = 34; @@ -162,32 +209,35 @@ int UavcanNode::run() { _node.setStatusOk(); + // XXX figure out the output count + _output_count = 2; + + _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); - while (true) { - + actuator_outputs_s outputs; + memset(&outputs, 0, sizeof(outputs)); + + while (!_task_should_exit) { + if (_groups_subscribed != _groups_required) { subscribe(); _groups_subscribed = _groups_required; - /* force setting update rate */ - _current_update_rate = 0; } int ret = ::poll(_poll_fds, _poll_fds_num, 5/* 5 ms wait time */); - /* this would be bad... */ + // this would be bad... if (ret < 0) { log("poll error %d", errno); - usleep(1000000); continue; } else if (ret == 0) { - /* timeout: no control data, switch to failsafe values */ -// warnx("no PWM: failsafe"); + // timeout: no control data, switch to failsafe values } else { - /* get controls for required topics */ + // get controls for required topics unsigned poll_id = 0; for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { @@ -198,7 +248,7 @@ int UavcanNode::run() } } - /* can we mix? */ + //can we mix? if (_mixers != nullptr) { // XXX one output group has 8 outputs max, @@ -209,9 +259,9 @@ int UavcanNode::run() outputs.noutputs = _mixers->mix(&outputs.output[0], num_outputs_max); outputs.timestamp = hrt_absolute_time(); - /* iterate actuators */ + // iterate actuators for (unsigned i = 0; i < outputs.noutputs; i++) { - /* last resort: catch NaN, INF and out-of-band errors */ + // last resort: catch NaN, INF and out-of-band errors if (!isfinite(outputs.output[i]) || outputs.output[i] < -1.0f || outputs.output[i] > 1.0f) { @@ -224,25 +274,25 @@ int UavcanNode::run() } } - printf("CAN out: ") + printf("CAN out: "); /* output to the bus */ for (unsigned i = 0; i < outputs.noutputs; i++) { - printf("%u: %8.4f ", i, outputs.output[i]) + printf("%u: %8.4f ", i, outputs.output[i]); // can_send_xxx } - printf("\n"); + printf("%s\n", (_is_armed) ? "ARMED" : "DISARMED"); } } - /* check arming state */ + // Check arming state bool updated = false; orb_check(_armed_sub, &updated); if (updated) { orb_copy(ORB_ID(actuator_armed), _armed_sub, &_armed); - /* update the armed status and check that we're not locked down */ + // Update the armed status and check that we're not locked down bool set_armed = _armed.armed && !_armed.lockdown; arm_actuators(set_armed); @@ -271,7 +321,7 @@ UavcanNode::control_callback(uintptr_t handle, { const actuator_controls_s *controls = (actuator_controls_s *)handle; - input = _controls[control_group].control[control_index]; + input = controls[control_group].control[control_index]; return 0; } @@ -287,22 +337,24 @@ UavcanNode::teardown() ::close(_armed_sub); } -void +int UavcanNode::arm_actuators(bool arm) { - bool changed = (_armed != arm); + bool changed = (_is_armed != arm); - _armed = arm; + _is_armed = arm; if (changed) { // Propagate immediately to CAN bus } + + return OK; } void UavcanNode::subscribe() { - /* subscribe/unsubscribe to required actuator control groups */ + // Subscribe/unsubscribe to required actuator control groups uint32_t sub_groups = _groups_required & ~_groups_subscribed; uint32_t unsub_groups = _groups_subscribed & ~_groups_required; _poll_fds_num = 0; @@ -326,7 +378,7 @@ UavcanNode::subscribe() } int -PX4FMU::pwm_ioctl(file *filp, int cmd, unsigned long arg) +UavcanNode::pwm_ioctl(file *filp, int cmd, unsigned long arg) { int ret = OK; diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 213cb4206..857c1dc66 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -33,8 +33,14 @@ #pragma once +#include + #include -#include +#include + +#include +#include +#include /** * @file uavcan_main.hpp @@ -44,6 +50,9 @@ * @author Pavel Kirienko */ +#define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4 +#define UAVCAN_DEVICE_PATH "/dev/uavcan" + /** * A UAVCAN node. */ @@ -57,21 +66,36 @@ public: typedef uavcan::Node Node; typedef uavcan_stm32::CanInitHelper CanInitHelper; - UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock); + UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock); + + virtual ~UavcanNode(); - static int start(uavcan::NodeID node_id, uint32_t bitrate); + static int start(uavcan::NodeID node_id, uint32_t bitrate); - Node &getNode() { return _node; } + Node& getNode() { return _node; } static int control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input); - void subscribe(); + + void subscribe(); + + int teardown(); + int arm_actuators(bool arm); private: - int init(uavcan::NodeID node_id); - int run(); + int init(uavcan::NodeID node_id); + int run(); + int pwm_ioctl(file *filp, int cmd, unsigned long arg); + + int _task; ///< handle to the OS task + bool _task_should_exit; ///< flag to indicate to tear down the CAN driver + int _armed_sub; ///< uORB subscription of the arming status + actuator_armed_s _armed; ///< the arming request of the system + bool _is_armed; ///< the arming status of the actuators on the bus + + unsigned _output_count; ///< number of actuators currently available static UavcanNode *_instance; ///< pointer to the library instance Node _node; @@ -80,9 +104,9 @@ private: uint32_t _groups_required; uint32_t _groups_subscribed; - int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS]; - actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS]; - orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS]; - pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS]; + int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; + actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; + orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; + pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; unsigned _poll_fds_num; }; -- cgit v1.2.3 From 185c95fda6acac869c1821846d44359faeef22d2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 8 May 2014 13:57:23 +0200 Subject: UAVCAN: improve printing, ready for full closed loop test --- src/modules/uavcan/uavcan_main.cpp | 46 +++++++++++++++++++++++++++++++++----- src/modules/uavcan/uavcan_main.hpp | 9 ++++++-- 2 files changed, 47 insertions(+), 8 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 332c3a5e8..a86314852 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -68,7 +68,11 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys _output_count(0), _node(can_driver, system_clock), _controls({}), - _poll_fds({}) + _poll_fds({}), + _mixers(nullptr), + _groups_required(0), + _groups_subscribed(0), + _poll_fds_num(0) { _control_topics[0] = ORB_ID(actuator_controls_0); _control_topics[1] = ORB_ID(actuator_controls_1); @@ -225,7 +229,7 @@ int UavcanNode::run() _groups_subscribed = _groups_required; } - int ret = ::poll(_poll_fds, _poll_fds_num, 5/* 5 ms wait time */); + int ret = ::poll(_poll_fds, _poll_fds_num, 50/* 50 ms wait time */); // this would be bad... if (ret < 0) { @@ -234,6 +238,7 @@ int UavcanNode::run() } else if (ret == 0) { // timeout: no control data, switch to failsafe values + // XXX trigger failsafe } else { @@ -278,11 +283,12 @@ int UavcanNode::run() /* output to the bus */ for (unsigned i = 0; i < outputs.noutputs; i++) { printf("%u: %8.4f ", i, outputs.output[i]); - // can_send_xxx + // XXX send out via CAN here } printf("%s\n", (_is_armed) ? "ARMED" : "DISARMED"); } + } // Check arming state @@ -300,7 +306,7 @@ int UavcanNode::run() // Output commands and fetch data - const int res = _node.spin(uavcan::MonotonicDuration::getInfinite()); + const int res = _node.spin(uavcan::MonotonicDuration::fromUSec(5000)); if (res < 0) { warnx("Spin error %i", res); @@ -309,6 +315,7 @@ int UavcanNode::run() } teardown(); + warnx("exiting."); exit(0); } @@ -378,7 +385,7 @@ UavcanNode::subscribe() } int -UavcanNode::pwm_ioctl(file *filp, int cmd, unsigned long arg) +UavcanNode::ioctl(file *filp, int cmd, unsigned long arg) { int ret = OK; @@ -428,7 +435,7 @@ UavcanNode::pwm_ioctl(file *filp, int cmd, unsigned long arg) ret = _mixers->load_from_buf(buf, buflen); if (ret != 0) { - debug("mixer load failed with %d", ret); + warnx("mixer load failed with %d", ret); delete _mixers; _mixers = nullptr; _groups_required = 0; @@ -449,9 +456,24 @@ UavcanNode::pwm_ioctl(file *filp, int cmd, unsigned long arg) unlock(); + if (ret == -ENOTTY) { + ret = CDev::ioctl(filp, cmd, arg); + } + return ret; } +void +UavcanNode::print_info() +{ + if (!_instance) { + warnx("not running, start first"); + } + + warnx("groups: sub: %u / req: %u / fds: %u", (unsigned)_groups_subscribed, (unsigned)_groups_required, _poll_fds_num); + warnx("mixer: %s", (_mixers == nullptr) ? "FAIL" : "OK"); +} + /* * App entry point */ @@ -511,5 +533,17 @@ int uavcan_main(int argc, char *argv[]) ::exit(1); } + /* commands below require the app to be started */ + UavcanNode *inst = UavcanNode::instance(); + + if (!inst) { + errx(1, "application not running"); + } + + if (!std::strcmp(argv[1], "status") || !std::strcmp(argv[1], "info")) { + + inst->print_info(); + } + return 0; } diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 857c1dc66..97598ddf3 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -66,10 +66,12 @@ public: typedef uavcan::Node Node; typedef uavcan_stm32::CanInitHelper CanInitHelper; - UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock); + UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock); virtual ~UavcanNode(); + virtual int ioctl(file *filp, int cmd, unsigned long arg); + static int start(uavcan::NodeID node_id, uint32_t bitrate); Node& getNode() { return _node; } @@ -84,10 +86,13 @@ public: int teardown(); int arm_actuators(bool arm); + void print_info(); + + static UavcanNode* instance() { return _instance; } + private: int init(uavcan::NodeID node_id); int run(); - int pwm_ioctl(file *filp, int cmd, unsigned long arg); int _task; ///< handle to the OS task bool _task_should_exit; ///< flag to indicate to tear down the CAN driver -- cgit v1.2.3 From f70db56e90972cf0492ac9d295c3d0f5df87aa66 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 8 May 2014 14:14:52 +0200 Subject: UAVCAN: Fix start / stop commands --- src/modules/uavcan/uavcan_main.cpp | 22 ++++++++++++++++------ 1 file changed, 16 insertions(+), 6 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index a86314852..9cd486bf5 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -92,8 +92,8 @@ UavcanNode::~UavcanNode() unsigned i = 10; do { - /* wait 50ms - it should wake every 100ms or so worst-case */ - usleep(50000); + /* wait 5ms - it should wake every 10ms or so worst-case */ + usleep(5000); /* if we have given up, kill it */ if (--i == 0) { @@ -522,15 +522,16 @@ int uavcan_main(int argc, char *argv[]) bitrate = DEFAULT_CAN_BITRATE; } + if (UavcanNode::instance()) { + errx(1, "already started"); + } + /* * Start */ warnx("Node ID %u, bitrate %u", node_id, bitrate); return UavcanNode::start(node_id, bitrate); - } else { - print_usage(); - ::exit(1); } /* commands below require the app to be started */ @@ -543,7 +544,16 @@ int uavcan_main(int argc, char *argv[]) if (!std::strcmp(argv[1], "status") || !std::strcmp(argv[1], "info")) { inst->print_info(); + return OK; } - return 0; + if (!std::strcmp(argv[1], "stop")) { + + delete inst; + inst = nullptr; + return OK; + } + + print_usage(); + ::exit(1); } -- cgit v1.2.3 From ec5602e45d51e500327bd3aa08d4a3d678573936 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 8 May 2014 14:23:33 +0200 Subject: UAVCAN quad X autostart setup --- ROMFS/px4fmu_common/init.d/4012_quad_x_can | 27 +++++++++++++++++++++++++++ ROMFS/px4fmu_common/init.d/rc.autostart | 5 +++++ ROMFS/px4fmu_common/init.d/rc.interface | 5 +++++ ROMFS/px4fmu_common/init.d/rcS | 12 +++++++++++- 4 files changed, 48 insertions(+), 1 deletion(-) create mode 100644 ROMFS/px4fmu_common/init.d/4012_quad_x_can diff --git a/ROMFS/px4fmu_common/init.d/4012_quad_x_can b/ROMFS/px4fmu_common/init.d/4012_quad_x_can new file mode 100644 index 000000000..471ac54b4 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/4012_quad_x_can @@ -0,0 +1,27 @@ +#!nsh +# +# F450-sized quadrotor with CAN +# +# Lorenz Meier +# + +sh /etc/init.d/4001_quad_x + +if [ $DO_AUTOCONFIG == yes ] +then + # TODO REVIEW + param set MC_ROLL_P 7.0 + param set MC_ROLLRATE_P 0.1 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.003 + param set MC_PITCH_P 7.0 + param set MC_PITCHRATE_P 0.1 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.003 + param set MC_YAW_P 2.8 + param set MC_YAWRATE_P 0.2 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 +fi + +set OUTPUT_MODE can diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart index 5ec735d39..3d0de950d 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart +++ b/ROMFS/px4fmu_common/init.d/rc.autostart @@ -136,6 +136,11 @@ then sh /etc/init.d/4011_dji_f450 fi +if param compare SYS_AUTOSTART 4012 +then + sh /etc/init.d/4012_quad_x_can +fi + # # Quad + # diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index 7f793b219..d6f1b54bc 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -24,6 +24,11 @@ then else set OUTPUT_DEV /dev/pwm_output fi + + if [ $OUTPUT_MODE == can ] + then + set OUTPUT_DEV /dev/uavcan + fi if mixer load $OUTPUT_DEV $MIXER_FILE then diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 756ee8ef8..5d76e4283 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -284,7 +284,17 @@ then # If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output if [ $OUTPUT_MODE != none ] then - if [ $OUTPUT_MODE == io ] + if [ $OUTPUT_MODE == can ] + then + if uavcan start 1 + then + echo "CAN UP" + else + echo "CAN ERR" + fi + fi + + if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == can ] then echo "[init] Use PX4IO PWM as primary output" if px4io start -- cgit v1.2.3 From 4055833c9e6b6ecadab44d231047c44796ff17bc Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 8 May 2014 17:03:40 +0400 Subject: UAVCAN mixer renamed to /dev/uavcan/esc --- ROMFS/px4fmu_common/init.d/rc.interface | 2 +- src/modules/uavcan/uavcan_main.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index d6f1b54bc..da4c73470 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -27,7 +27,7 @@ then if [ $OUTPUT_MODE == can ] then - set OUTPUT_DEV /dev/uavcan + set OUTPUT_DEV /dev/uavcan/esc fi if mixer load $OUTPUT_DEV $MIXER_FILE diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 97598ddf3..beaa5e1d4 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -51,7 +51,7 @@ */ #define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 4 -#define UAVCAN_DEVICE_PATH "/dev/uavcan" +#define UAVCAN_DEVICE_PATH "/dev/uavcan/esc" /** * A UAVCAN node. -- cgit v1.2.3 From f4c28473f9038875a56eace4b9b7364694bb03df Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 8 May 2014 17:12:05 +0400 Subject: Warning fixes --- src/modules/uavcan/uavcan_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 9cd486bf5..859db93c7 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -336,12 +336,12 @@ int UavcanNode::teardown() { for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { - if (_control_subs > 0) { + if (_control_subs[i] > 0) { ::close(_control_subs[i]); _control_subs[i] = -1; } } - ::close(_armed_sub); + return ::close(_armed_sub); } int -- cgit v1.2.3 From 4a98dae227f3e60f1a220164bce0b995ce303f3d Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 8 May 2014 19:42:20 +0400 Subject: UAVCAN ESC controller - proof of concept state --- src/modules/uavcan/esc_controller.cpp | 124 ++++++++++++++++++++++++++++++++++ src/modules/uavcan/esc_controller.hpp | 99 +++++++++++++++++++++++++++ src/modules/uavcan/module.mk | 5 +- src/modules/uavcan/uavcan_main.cpp | 47 ++++++------- src/modules/uavcan/uavcan_main.hpp | 35 +++++----- 5 files changed, 265 insertions(+), 45 deletions(-) create mode 100644 src/modules/uavcan/esc_controller.cpp create mode 100644 src/modules/uavcan/esc_controller.hpp diff --git a/src/modules/uavcan/esc_controller.cpp b/src/modules/uavcan/esc_controller.cpp new file mode 100644 index 000000000..bde4d2a7f --- /dev/null +++ b/src/modules/uavcan/esc_controller.cpp @@ -0,0 +1,124 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file esc_controller.cpp + * + * @author Pavel Kirienko + */ + +#include "esc_controller.hpp" +#include + +UavcanEscController::UavcanEscController(uavcan::INode &node) : + _node(node), + _uavcan_pub_raw_cmd(node), + _uavcan_sub_status(node), + _orb_timer(node) +{ +} + +int UavcanEscController::init() +{ + int res = -1; + + // ESC status subscription + res = _uavcan_sub_status.start(StatusCbBinder(this, &UavcanEscController::esc_status_sub_cb)); + if (res < 0) + { + warnx("ESC status sub failed %i", res); + return res; + } + + // ESC status will be relayed from UAVCAN bus into ORB at this rate + _orb_timer.setCallback(TimerCbBinder(this, &UavcanEscController::orb_pub_timer_cb)); + _orb_timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / ESC_STATUS_UPDATE_RATE_HZ)); + + return res; +} + +void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) +{ + assert(outputs != nullptr); + assert(num_outputs <= MAX_ESCS); + + /* + * Rate limiting - we don't want to congest the bus + */ + const auto timestamp = _node.getMonotonicTime(); + if ((timestamp - _prev_cmd_pub).toUSec() < (1000000 / MAX_RATE_HZ)) { + return; + } + _prev_cmd_pub = timestamp; + + /* + * Fill the command message + * If unarmed, we publish an empty message anyway + */ + uavcan::equipment::esc::RawCommand msg; + + if (_armed) { + for (unsigned i = 0; i < num_outputs; i++) { + + float scaled = (outputs[i] + 1.0F) * 0.5F * uavcan::equipment::esc::RawCommand::CMD_MAX; + if (scaled < 1.0F) + scaled = 1.0F; // Since we're armed, we don't want to stop it completely + + assert(scaled >= uavcan::equipment::esc::RawCommand::CMD_MIN); + assert(scaled <= uavcan::equipment::esc::RawCommand::CMD_MAX); + + msg.cmd.push_back(scaled); + } + } + + /* + * Publish the command message to the bus + * Note that for a quadrotor it takes one CAN frame + */ + (void)_uavcan_pub_raw_cmd.broadcast(msg); +} + +void UavcanEscController::arm_esc(bool arm) +{ + _armed = arm; +} + +void UavcanEscController::esc_status_sub_cb(const uavcan::ReceivedDataStructure &msg) +{ + // TODO save status into a local storage; publish to ORB later from orb_pub_timer_cb() +} + +void UavcanEscController::orb_pub_timer_cb(const uavcan::TimerEvent&) +{ + // TODO publish to ORB +} diff --git a/src/modules/uavcan/esc_controller.hpp b/src/modules/uavcan/esc_controller.hpp new file mode 100644 index 000000000..0ed0c59b5 --- /dev/null +++ b/src/modules/uavcan/esc_controller.hpp @@ -0,0 +1,99 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file esc_controller.hpp + * + * UAVCAN <--> ORB bridge for ESC messages: + * uavcan.equipment.esc.RawCommand + * uavcan.equipment.esc.RPMCommand + * uavcan.equipment.esc.Status + * + * @author Pavel Kirienko + */ + +#pragma once + +#include +#include +#include + +class UavcanEscController +{ +public: + UavcanEscController(uavcan::INode& node); + + int init(); + + void update_outputs(float *outputs, unsigned num_outputs); + + void arm_esc(bool arm); + +private: + /** + * ESC status message reception will be reported via this callback. + */ + void esc_status_sub_cb(const uavcan::ReceivedDataStructure &msg); + + /** + * ESC status will be published to ORB from this callback (fixed rate). + */ + void orb_pub_timer_cb(const uavcan::TimerEvent &event); + + + static constexpr unsigned MAX_RATE_HZ = 100; ///< XXX make this configurable + static constexpr unsigned ESC_STATUS_UPDATE_RATE_HZ = 5; + static constexpr unsigned MAX_ESCS = uavcan::equipment::esc::RawCommand::FieldTypes::cmd::MaxSize; + + typedef uavcan::MethodBinder&)> + StatusCbBinder; + + typedef uavcan::MethodBinder + TimerCbBinder; + + /* + * libuavcan related things + */ + uavcan::MonotonicTime _prev_cmd_pub; ///< rate limiting + uavcan::INode &_node; + uavcan::Publisher _uavcan_pub_raw_cmd; + uavcan::Subscriber _uavcan_sub_status; + uavcan::TimerEventForwarder _orb_timer; + + /* + * ESC states + */ + bool _armed = false; + uavcan::equipment::esc::Status _states[MAX_ESCS]; +}; diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index 098543879..ce9f981a8 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -40,8 +40,9 @@ MODULE_COMMAND = uavcan MAXOPTIMIZATION = -Os -SRCS += uavcan_main.cpp \ - uavcan_clock.cpp +SRCS += uavcan_main.cpp \ + uavcan_clock.cpp \ + esc_controller.cpp # # libuavcan diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 859db93c7..e7829cbba 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -61,18 +61,8 @@ UavcanNode *UavcanNode::_instance; UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) : CDev("uavcan", UAVCAN_DEVICE_PATH), - _task(0), - _task_should_exit(false), - _armed_sub(-1), - _is_armed(false), - _output_count(0), _node(can_driver, system_clock), - _controls({}), - _poll_fds({}), - _mixers(nullptr), - _groups_required(0), - _groups_subscribed(0), - _poll_fds_num(0) + _esc_controller(_node) { _control_topics[0] = ORB_ID(actuator_controls_0); _control_topics[1] = ORB_ID(actuator_controls_1); @@ -183,8 +173,7 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) int UavcanNode::init(uavcan::NodeID node_id) { - - int ret; + int ret = -1; /* do regular cdev init */ ret = CDev::init(); @@ -192,6 +181,10 @@ int UavcanNode::init(uavcan::NodeID node_id) if (ret != OK) return ret; + ret = _esc_controller.init(); + if (ret < 0) + return ret; + uavcan::protocol::SoftwareVersion swver; swver.major = 12; // TODO fill version info swver.minor = 34; @@ -222,6 +215,11 @@ int UavcanNode::run() actuator_outputs_s outputs; memset(&outputs, 0, sizeof(outputs)); + /* + * XXX Mixing logic/subscriptions shall be moved into UavcanEscController::update(); + * IO multiplexing shall be done here. + */ + while (!_task_should_exit) { if (_groups_subscribed != _groups_required) { @@ -279,14 +277,16 @@ int UavcanNode::run() } } + /* + * Output to the bus + */ printf("CAN out: "); - /* output to the bus */ for (unsigned i = 0; i < outputs.noutputs; i++) { printf("%u: %8.4f ", i, outputs.output[i]); - // XXX send out via CAN here } printf("%s\n", (_is_armed) ? "ARMED" : "DISARMED"); + _esc_controller.update_outputs(outputs.output, outputs.noutputs); } } @@ -304,13 +304,12 @@ int UavcanNode::run() arm_actuators(set_armed); } - // Output commands and fetch data + // Output commands and fetch data TODO ORB multiplexing - const int res = _node.spin(uavcan::MonotonicDuration::fromUSec(5000)); + const int spin_res = _node.spin(uavcan::MonotonicDuration::fromMSec(1)); - if (res < 0) { - warnx("Spin error %i", res); - ::sleep(1); + if (spin_res < 0) { + warnx("node spin error %i", spin_res); } } @@ -347,14 +346,8 @@ UavcanNode::teardown() int UavcanNode::arm_actuators(bool arm) { - bool changed = (_is_armed != arm); - _is_armed = arm; - - if (changed) { - // Propagate immediately to CAN bus - } - + _esc_controller.arm_esc(arm); return OK; } diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index beaa5e1d4..f4a709c79 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -42,6 +42,8 @@ #include #include +#include "esc_controller.hpp" + /** * @file uavcan_main.hpp * @@ -94,24 +96,25 @@ private: int init(uavcan::NodeID node_id); int run(); - int _task; ///< handle to the OS task - bool _task_should_exit; ///< flag to indicate to tear down the CAN driver - int _armed_sub; ///< uORB subscription of the arming status - actuator_armed_s _armed; ///< the arming request of the system - bool _is_armed; ///< the arming status of the actuators on the bus + int _task = -1; ///< handle to the OS task + bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver + int _armed_sub = -1; ///< uORB subscription of the arming status + actuator_armed_s _armed; ///< the arming request of the system + bool _is_armed = false; ///< the arming status of the actuators on the bus - unsigned _output_count; ///< number of actuators currently available + unsigned _output_count = 0; ///< number of actuators currently available - static UavcanNode *_instance; ///< pointer to the library instance - Node _node; + static UavcanNode *_instance; ///< singleton pointer + Node _node; ///< library instance + UavcanEscController _esc_controller; - MixerGroup *_mixers; + MixerGroup *_mixers = nullptr; - uint32_t _groups_required; - uint32_t _groups_subscribed; - int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; - actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; - orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; - pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN]; - unsigned _poll_fds_num; + uint32_t _groups_required = 0; + uint32_t _groups_subscribed = 0; + int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {}; + actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {}; + orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {}; + pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {}; + unsigned _poll_fds_num = 0; }; -- cgit v1.2.3 From c697aae17a32f25b2f163282b9cb18efedb14d77 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 8 May 2014 23:34:23 +0400 Subject: Proper IO miltiplexing libuavcan + ORB --- src/modules/uavcan/uavcan_main.cpp | 68 +++++++++++++++++++++++--------------- src/modules/uavcan/uavcan_main.hpp | 3 +- 2 files changed, 44 insertions(+), 27 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index e7829cbba..6ba596ad0 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -35,6 +35,7 @@ #include #include +#include #include #include #include @@ -202,9 +203,17 @@ int UavcanNode::init(uavcan::NodeID node_id) return _node.start(); } +void UavcanNode::node_spin_once() +{ + const int spin_res = _node.spin(uavcan::MonotonicTime()); + if (spin_res < 0) { + warnx("node spin error %i", spin_res); + } +} + int UavcanNode::run() { - _node.setStatusOk(); + const unsigned PollTimeoutMs = 50; // XXX figure out the output count _output_count = 2; @@ -215,42 +224,65 @@ int UavcanNode::run() actuator_outputs_s outputs; memset(&outputs, 0, sizeof(outputs)); + const int busevent_fd = ::open(uavcan_stm32::Event::DevName, 0); + if (busevent_fd < 0) + { + warnx("Failed to open %s", uavcan_stm32::Event::DevName); + _task_should_exit = true; + } + /* * XXX Mixing logic/subscriptions shall be moved into UavcanEscController::update(); * IO multiplexing shall be done here. */ + _node.setStatusOk(); + while (!_task_should_exit) { if (_groups_subscribed != _groups_required) { subscribe(); _groups_subscribed = _groups_required; + /* + * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error). + * Actual event type (POLLIN/POLLOUT/...) doesn't matter here. + * Please note that with such multiplexing it is no longer possible to rely only on + * the value returned from poll() to detect whether actuator control has timed out or not. + * Instead, all ORB events need to be checked individually (see below). + */ + _poll_fds[_poll_fds_num] = ::pollfd(); + _poll_fds[_poll_fds_num].fd = busevent_fd; + _poll_fds[_poll_fds_num].events = POLLIN | POLLOUT; + _poll_fds_num += 1; } - int ret = ::poll(_poll_fds, _poll_fds_num, 50/* 50 ms wait time */); + const int poll_ret = ::poll(_poll_fds, _poll_fds_num, PollTimeoutMs); + + node_spin_once(); // Non-blocking // this would be bad... - if (ret < 0) { + if (poll_ret < 0) { log("poll error %d", errno); continue; - - } else if (ret == 0) { - // timeout: no control data, switch to failsafe values - // XXX trigger failsafe - } else { - // get controls for required topics + bool controls_updated = false; unsigned poll_id = 0; for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { if (_poll_fds[poll_id].revents & POLLIN) { + controls_updated = true; orb_copy(_control_topics[i], _control_subs[i], &_controls[i]); } poll_id++; } } + if (!controls_updated) { + // timeout: no control data, switch to failsafe values + // XXX trigger failsafe + } + //can we mix? if (_mixers != nullptr) { @@ -277,15 +309,7 @@ int UavcanNode::run() } } - /* - * Output to the bus - */ - printf("CAN out: "); - for (unsigned i = 0; i < outputs.noutputs; i++) { - printf("%u: %8.4f ", i, outputs.output[i]); - } - printf("%s\n", (_is_armed) ? "ARMED" : "DISARMED"); - + // Output to the bus _esc_controller.update_outputs(outputs.output, outputs.noutputs); } @@ -303,14 +327,6 @@ int UavcanNode::run() arm_actuators(set_armed); } - - // Output commands and fetch data TODO ORB multiplexing - - const int spin_res = _node.spin(uavcan::MonotonicDuration::fromMSec(1)); - - if (spin_res < 0) { - warnx("node spin error %i", spin_res); - } } teardown(); diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index f4a709c79..751a94a8a 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -94,6 +94,7 @@ public: private: int init(uavcan::NodeID node_id); + void node_spin_once(); int run(); int _task = -1; ///< handle to the OS task @@ -115,6 +116,6 @@ private: int _control_subs[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {}; actuator_controls_s _controls[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {}; orb_id_t _control_topics[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {}; - pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN] = {}; + pollfd _poll_fds[NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN + 1] = {}; ///< +1 for /dev/uavcan/busevent unsigned _poll_fds_num = 0; }; -- cgit v1.2.3 From 5a905825675a33b210469eff96f0b82a8bd70eb9 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 9 May 2014 02:18:45 +0400 Subject: Catching up with STM32 driver optimizations in libuavcan --- src/modules/uavcan/uavcan_main.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 6ba596ad0..d4a0d894a 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -224,10 +224,10 @@ int UavcanNode::run() actuator_outputs_s outputs; memset(&outputs, 0, sizeof(outputs)); - const int busevent_fd = ::open(uavcan_stm32::Event::DevName, 0); + const int busevent_fd = ::open(uavcan_stm32::BusEvent::DevName, 0); if (busevent_fd < 0) { - warnx("Failed to open %s", uavcan_stm32::Event::DevName); + warnx("Failed to open %s", uavcan_stm32::BusEvent::DevName); _task_should_exit = true; } @@ -252,7 +252,7 @@ int UavcanNode::run() */ _poll_fds[_poll_fds_num] = ::pollfd(); _poll_fds[_poll_fds_num].fd = busevent_fd; - _poll_fds[_poll_fds_num].events = POLLIN | POLLOUT; + _poll_fds[_poll_fds_num].events = POLLIN; _poll_fds_num += 1; } -- cgit v1.2.3 From 8501158427d7cf96b125eafe48193f654c7fb2f0 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 9 May 2014 02:23:52 +0400 Subject: Micro optimization in UAVCAN polling loop --- src/modules/uavcan/uavcan_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index d4a0d894a..73f519fa1 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -284,7 +284,7 @@ int UavcanNode::run() } //can we mix? - if (_mixers != nullptr) { + if (controls_updated && (_mixers != nullptr)) { // XXX one output group has 8 outputs max, // but this driver could well serve multiple groups. -- cgit v1.2.3 From 4edc432f399297ed6e74685408e80c0640873099 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 9 May 2014 02:24:46 +0400 Subject: Removed misleading comment --- src/modules/uavcan/uavcan_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 73f519fa1..ab687a6b9 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -245,7 +245,6 @@ int UavcanNode::run() _groups_subscribed = _groups_required; /* * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error). - * Actual event type (POLLIN/POLLOUT/...) doesn't matter here. * Please note that with such multiplexing it is no longer possible to rely only on * the value returned from poll() to detect whether actuator control has timed out or not. * Instead, all ORB events need to be checked individually (see below). -- cgit v1.2.3 From 559c62b6bc4923854e106be5987db92197e0bae1 Mon Sep 17 00:00:00 2001 From: TickTock- Date: Fri, 9 May 2014 15:17:38 -0700 Subject: Changed low threshold in px4io firmware to 10% to ensure compatibility with user configured single channel, mode switches --- src/modules/px4iofirmware/controls.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/px4iofirmware/controls.c b/src/modules/px4iofirmware/controls.c index 56c5aa005..a8c560d40 100644 --- a/src/modules/px4iofirmware/controls.c +++ b/src/modules/px4iofirmware/controls.c @@ -47,8 +47,8 @@ #include "px4io.h" #define RC_FAILSAFE_TIMEOUT 2000000 /**< two seconds failsafe timeout */ -#define RC_CHANNEL_HIGH_THRESH 5000 -#define RC_CHANNEL_LOW_THRESH -5000 +#define RC_CHANNEL_HIGH_THRESH 5000 /* 75% threshold */ +#define RC_CHANNEL_LOW_THRESH -8000 /* 10% threshold */ static bool ppm_input(uint16_t *values, uint16_t *num_values, uint16_t *frame_len); -- cgit v1.2.3 From 78637ff74b4c12edca0fac9ea8eb65f38993b49f Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 21 May 2014 11:14:06 +0200 Subject: mavlink: publish attitude / rates setpoint in offboard control mode --- src/modules/mavlink/mavlink_receiver.cpp | 72 +++++++++++++++++++++++++++++--- src/modules/mavlink/mavlink_receiver.h | 7 ++++ 2 files changed, 74 insertions(+), 5 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 72b9ee83a..561744755 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -102,16 +102,21 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) : _cmd_pub(-1), _flow_pub(-1), _offboard_control_sp_pub(-1), + _att_sp_pub(-1), + _rates_sp_pub(-1), _vicon_position_pub(-1), _telemetry_status_pub(-1), _rc_pub(-1), _manual_pub(-1), + _control_mode_sub(-1), _hil_frames(0), _old_timestamp(0), _hil_local_proj_inited(0), _hil_local_alt0(0.0) { + _control_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); memset(&hil_local_pos, 0, sizeof(hil_local_pos)); + memset(&_control_mode, 0, sizeof(_control_mode)); } MavlinkReceiver::~MavlinkReceiver() @@ -349,33 +354,33 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message struct offboard_control_setpoint_s offboard_control_sp; memset(&offboard_control_sp, 0, sizeof(offboard_control_sp)); - uint8_t ml_mode = 0; + enum OFFBOARD_CONTROL_MODE ml_mode = OFFBOARD_CONTROL_MODE_DIRECT; bool ml_armed = false; switch (quad_motors_setpoint.mode) { case 0: - ml_armed = false; break; case 1: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES; ml_armed = true; - break; case 2: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; ml_armed = true; - break; case 3: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY; + ml_armed = true; break; case 4: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION; break; + default: + break; } offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX; @@ -388,7 +393,7 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message } offboard_control_sp.armed = ml_armed; - offboard_control_sp.mode = static_cast(ml_mode); + offboard_control_sp.mode = ml_mode; offboard_control_sp.timestamp = hrt_absolute_time(); @@ -398,6 +403,63 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message } else { orb_publish(ORB_ID(offboard_control_setpoint), _offboard_control_sp_pub, &offboard_control_sp); } + + bool updated; + orb_check(_control_mode_sub, &updated); + if (updated) { + orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); + + if (_control_mode.flag_control_offboard_enabled) { + if (_control_mode.flag_control_position_enabled) { + // TODO + + } else if (_control_mode.flag_control_velocity_enabled) { + // TODO + + } else if (_control_mode.flag_control_attitude_enabled) { + /* attitude control */ + struct vehicle_attitude_setpoint_s att_sp; + memset(&att_sp, 0, sizeof(att_sp)); + + att_sp.roll_body = offboard_control_sp.p1; + att_sp.pitch_body = offboard_control_sp.p2; + att_sp.yaw_body = offboard_control_sp.p3; + att_sp.thrust = offboard_control_sp.p4; + + att_sp.timestamp = hrt_absolute_time(); + + if (_att_sp_pub < 0) { + _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); + + } else { + orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &att_sp); + } + + } else if (_control_mode.flag_control_rates_enabled) { + /* rates control */ + struct vehicle_rates_setpoint_s rates_sp; + memset(&rates_sp, 0, sizeof(rates_sp)); + + rates_sp.roll = offboard_control_sp.p1; + rates_sp.pitch = offboard_control_sp.p2; + rates_sp.yaw = offboard_control_sp.p3; + rates_sp.thrust = offboard_control_sp.p4; + + rates_sp.timestamp = hrt_absolute_time(); + + if (_rates_sp_pub < 0) { + _rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); + + } else { + orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &rates_sp); + } + + } else { + /* direct control */ + // TODO + } + } + } } } diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index 9ab84b58a..dc31b4c5a 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -36,6 +36,7 @@ * MAVLink 1.0 uORB listener definition * * @author Lorenz Meier + * @author Anton Babushkin */ #pragma once @@ -44,6 +45,7 @@ #include #include #include +#include #include #include #include @@ -120,6 +122,7 @@ private: mavlink_status_t status; struct vehicle_local_position_s hil_local_pos; + struct vehicle_control_mode_s _control_mode; orb_advert_t _global_pos_pub; orb_advert_t _local_pos_pub; orb_advert_t _attitude_pub; @@ -134,10 +137,14 @@ private: orb_advert_t _cmd_pub; orb_advert_t _flow_pub; orb_advert_t _offboard_control_sp_pub; + orb_advert_t _att_sp_pub; + orb_advert_t _rates_sp_pub; orb_advert_t _vicon_position_pub; orb_advert_t _telemetry_status_pub; orb_advert_t _rc_pub; orb_advert_t _manual_pub; + + int _control_mode_sub; int _hil_frames; uint64_t _old_timestamp; bool _hil_local_proj_inited; -- cgit v1.2.3 From 6df2fe9aebb008932055b85f134908127d8b3931 Mon Sep 17 00:00:00 2001 From: Kynos Date: Thu, 29 May 2014 21:23:57 +0200 Subject: U-blox driver rework, step 1 Handle u-blox 7+8 GNSS, too. Disabled NAV-SVINFO for now (will be rewritten as an optional feature in a later step). Reduced parser buffer size from 300 to 80. --- src/drivers/gps/ubx.cpp | 37 ++++++++++++++++++++++++--------- src/drivers/gps/ubx.h | 55 ++++++++++++++++++++++++++++++++++++++++++------- 2 files changed, 74 insertions(+), 18 deletions(-) diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index 19cf5beec..ee53e2ec4 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -219,12 +219,14 @@ UBX::configure(unsigned &baudrate) return 1; } +#ifdef UBX_ENABLE_NAV_SVINFO configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5); if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { warnx("MSG CFG FAIL: NAV SVINFO"); return 1; } +#endif configure_message_rate(UBX_CLASS_MON, UBX_MESSAGE_MON_HW, 1); @@ -386,7 +388,6 @@ UBX::parse_char(uint8_t b) if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes /* compare checksum */ if (_rx_ck_a == _rx_buffer[_rx_count - 1] && _rx_ck_b == _rx_buffer[_rx_count]) { - decode_init(); return 1; // message received successfully } else { @@ -399,7 +400,7 @@ UBX::parse_char(uint8_t b) _rx_count++; } else { - warnx("buffer full"); + warnx("ubx: buffer full 0x%02x-0x%02x L%u", (unsigned)_message_class, (unsigned)_message_id, _payload_size); decode_init(); return -1; } @@ -450,6 +451,7 @@ UBX::handle_message() _gps_position->s_variance_m_s = packet->sAcc; _gps_position->p_variance_m = packet->pAcc; _gps_position->timestamp_variance = hrt_absolute_time(); + _gps_position->satellites_visible = packet->numSV; ret = 1; break; @@ -486,6 +488,7 @@ UBX::handle_message() break; } +#ifdef UBX_ENABLE_NAV_SVINFO case UBX_MESSAGE_NAV_SVINFO: { //printf("GOT NAV_SVINFO\n"); const int length_part1 = 8; @@ -527,7 +530,9 @@ UBX::handle_message() _gps_position->satellite_azimuth[i] = 0; } - _gps_position->satellites_visible = satellites_used; // visible ~= used but we are interested in the used ones + /* Note: _gps_position->satellites_visible is taken from NAV-SOL now. */ + /* _gps_position->satellites_visible = satellites_used; */ // visible ~= used but we are interested in the used ones + /* TODO: satellites_used may be written into a new field after sat monitoring data got separated from _gps_position */ if (packet_part1->numCh > 0) { _gps_position->satellite_info_available = true; @@ -541,6 +546,7 @@ UBX::handle_message() ret = 1; break; } +#endif /* #ifdef UBX_ENABLE_NAV_SVINFO */ case UBX_MESSAGE_NAV_VELNED: { // printf("GOT NAV_VELNED\n"); @@ -573,23 +579,34 @@ UBX::handle_message() break; } - case UBX_CLASS_MON: { + case UBX_CLASS_MON: switch (_message_id) { - case UBX_MESSAGE_MON_HW: { - struct gps_bin_mon_hw_packet *p = (struct gps_bin_mon_hw_packet*) _rx_buffer; + case UBX_MESSAGE_MON_HW: + switch (_payload_size) { - _gps_position->noise_per_ms = p->noisePerMS; - _gps_position->jamming_indicator = p->jamInd; + case UBX_MON_HW_UBX6_RX_PAYLOAD_SIZE: /* u-blox 6 msg format */ + _gps_position->noise_per_ms = ((struct gps_bin_mon_hw_ubx6_packet*) _rx_buffer)->noisePerMS; + _gps_position->jamming_indicator = ((struct gps_bin_mon_hw_ubx6_packet*) _rx_buffer)->jamInd; + ret = 1; + break; + case UBX_MON_HW_UBX7_RX_PAYLOAD_SIZE: /* u-blox 7+ msg format */ + _gps_position->noise_per_ms = ((struct gps_bin_mon_hw_ubx7_packet*) _rx_buffer)->noisePerMS; + _gps_position->jamming_indicator = ((struct gps_bin_mon_hw_ubx7_packet*) _rx_buffer)->jamInd; ret = 1; break; + + default: // unexpected payload size: + ret = 1; // ignore but don't disable msg + break; } + break; default: break; } - } + break; default: break; @@ -597,7 +614,7 @@ UBX::handle_message() if (ret == 0) { /* message not handled */ - warnx("ubx: unknown message received: 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id); + warnx("ubx: message not handled: 0x%02x-0x%02x L%u", (unsigned)_message_class, (unsigned)_message_id, _payload_size); hrt_abstime t = hrt_absolute_time(); diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index 5cf47b60b..56f73fa63 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -48,6 +48,10 @@ #include "gps_helper.h" +/* TODO: processing of NAV_SVINFO disabled, has to be re-written as an optional feature */ +/* TODO: make this a command line option, allocate buffer dynamically */ +#undef UBX_ENABLE_NAV_SVINFO + #define UBX_SYNC1 0xB5 #define UBX_SYNC2 0x62 @@ -60,10 +64,8 @@ /* MessageIDs (the ones that are used) */ #define UBX_MESSAGE_NAV_POSLLH 0x02 -//#define UBX_MESSAGE_NAV_DOP 0x04 #define UBX_MESSAGE_NAV_SOL 0x06 #define UBX_MESSAGE_NAV_VELNED 0x12 -//#define UBX_MESSAGE_RXM_SVSI 0x20 #define UBX_MESSAGE_NAV_TIMEUTC 0x21 #define UBX_MESSAGE_NAV_SVINFO 0x30 #define UBX_MESSAGE_ACK_NAK 0x00 @@ -72,9 +74,22 @@ #define UBX_MESSAGE_CFG_MSG 0x01 #define UBX_MESSAGE_CFG_RATE 0x08 #define UBX_MESSAGE_CFG_NAV5 0x24 - #define UBX_MESSAGE_MON_HW 0x09 +/* Rx msg payload sizes */ +#define UBX_NAV_POSLLH_RX_PAYLOAD_SIZE 28 /**< NAV_POSLLH Rx msg payload size */ +#define UBX_NAV_SOL_RX_PAYLOAD_SIZE 52 /**< NAV_SOL Rx msg payload size */ +#define UBX_NAV_VELNED_RX_PAYLOAD_SIZE 36 /**< NAV_VELNED Rx msg payload size */ +#define UBX_NAV_TIMEUTC_RX_PAYLOAD_SIZE 20 /**< NAV_TIMEUTC Rx msg payload size */ +#define UBX_MON_HW_UBX6_RX_PAYLOAD_SIZE 68 /**< MON_HW Rx msg payload size for u-blox 6 and below */ +#define UBX_MON_HW_UBX7_RX_PAYLOAD_SIZE 60 /**< MON_HW Rx msg payload size for u-blox 7 and above */ +#define UBX_MAX_RX_PAYLOAD_SIZE 70 /**< arbitrary maximum for calculating parser buffer size w/o NAV_SVINFO active */ + +/* NAV_SVINFO has variable length w/o a published max size, so limit processing to UBX_MAX_NUM_SAT */ +#define UBX_MAX_NUM_SAT 50 /**< Practical observed max number of satellites in SVNFO msg */ +#define UBX_NAV_SVINFO_RX_PAYLOAD_SIZE (8 + 12 * UBX_MAX_NUM_SAT) /**< NAV_SVINFO Rx msg payload size */ + +/* CFG class Tx msg defs */ #define UBX_CFG_PRT_LENGTH 20 #define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */ #define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ @@ -87,7 +102,6 @@ #define UBX_CFG_RATE_PAYLOAD_NAVRATE 1 /**< cannot be changed */ #define UBX_CFG_RATE_PAYLOAD_TIMEREF 0 /**< 0: UTC, 1: GPS time */ - #define UBX_CFG_NAV5_LENGTH 36 #define UBX_CFG_NAV5_PAYLOAD_MASK 0x0005 /**< XXX only update dynamic model and fix mode */ #define UBX_CFG_NAV5_PAYLOAD_DYNMODEL 7 /**< 0: portable, 2: stationary, 3: pedestrian, 4: automotive, 5: sea, 6: airborne <1g, 7: airborne <2g, 8: airborne <4g */ @@ -98,7 +112,6 @@ #define UBX_CFG_MSG_PAYLOAD_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ #define UBX_CFG_MSG_PAYLOAD_RATE1_05HZ 10 -#define UBX_MAX_PAYLOAD_LENGTH 500 // ************ /** the structures of the binary packets */ @@ -140,7 +153,7 @@ typedef struct { uint32_t sAcc; uint16_t pDOP; uint8_t reserved1; - uint8_t numSV; + uint8_t numSV; /**< Number of SVs used in Nav Solution */ uint32_t reserved2; uint8_t ck_a; uint8_t ck_b; @@ -213,7 +226,7 @@ typedef struct { uint8_t ck_b; } gps_bin_nav_velned_packet_t; -struct gps_bin_mon_hw_packet { +struct gps_bin_mon_hw_ubx6_packet { uint32_t pinSel; uint32_t pinBank; uint32_t pinDir; @@ -233,6 +246,25 @@ struct gps_bin_mon_hw_packet { uint32_t pullL; }; +struct gps_bin_mon_hw_ubx7_packet { + uint32_t pinSel; + uint32_t pinBank; + uint32_t pinDir; + uint32_t pinVal; + uint16_t noisePerMS; + uint16_t agcCnt; + uint8_t aStatus; + uint8_t aPower; + uint8_t flags; + uint8_t __reserved1; + uint32_t usedMask; + uint8_t VP[17]; + uint8_t jamInd; + uint16_t __reserved3; + uint32_t pinIrq; + uint32_t pulLH; + uint32_t pullL; +}; //typedef struct { // int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */ @@ -343,7 +375,14 @@ typedef enum { //typedef type_gps_bin_ubx_state gps_bin_ubx_state_t; #pragma pack(pop) -#define RECV_BUFFER_SIZE 300 //The NAV-SOL messages really need such a big buffer +/* calculate parser rx buffer size dependent on NAV_SVINFO enabled or not */ +/* TODO: make this a command line option, allocate buffer dynamically */ +#define RECV_BUFFER_OVERHEAD 10 // add this to the maximum Rx msg payload size to account for msg overhead */ +#ifdef UBX_ENABLE_NAV_SVINFO + #define RECV_BUFFER_SIZE (UBX_NAV_SVINFO_RX_PAYLOAD_SIZE + RECV_BUFFER_OVERHEAD) +#else + #define RECV_BUFFER_SIZE (UBX_MAX_RX_PAYLOAD_SIZE + RECV_BUFFER_OVERHEAD) +#endif class UBX : public GPS_Helper { -- cgit v1.2.3 From 7349fa90376714b00fe920538950b31a46169d60 Mon Sep 17 00:00:00 2001 From: Kynos Date: Fri, 30 May 2014 11:03:16 +0200 Subject: Beautifications for tab size 8 Beautifications for tab size 8 --- src/drivers/gps/ubx.cpp | 6 ++-- src/drivers/gps/ubx.h | 74 ++++++++++++++++++++++++------------------------- 2 files changed, 40 insertions(+), 40 deletions(-) diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index ee53e2ec4..d7e9454ae 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -59,10 +59,10 @@ #include "ubx.h" -#define UBX_CONFIG_TIMEOUT 200 // ms, timeout for waiting ACK -#define UBX_PACKET_TIMEOUT 2 // ms, if now data during this delay assume that full update received +#define UBX_CONFIG_TIMEOUT 200 // ms, timeout for waiting ACK +#define UBX_PACKET_TIMEOUT 2 // ms, if now data during this delay assume that full update received #define UBX_WAIT_BEFORE_READ 20 // ms, wait before reading to save read() calls -#define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval +#define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) : _fd(fd), diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index 56f73fa63..b844c315e 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -34,7 +34,7 @@ /** * @file ubx.h * - * U-Blox protocol definition. Following u-blox 6/7 Receiver Description + * U-Blox protocol definition. Following u-blox 6/7/8 Receiver Description * including Prototol Specification. * * @author Thomas Gubler @@ -86,7 +86,7 @@ #define UBX_MAX_RX_PAYLOAD_SIZE 70 /**< arbitrary maximum for calculating parser buffer size w/o NAV_SVINFO active */ /* NAV_SVINFO has variable length w/o a published max size, so limit processing to UBX_MAX_NUM_SAT */ -#define UBX_MAX_NUM_SAT 50 /**< Practical observed max number of satellites in SVNFO msg */ +#define UBX_MAX_NUM_SAT 50 /**< Practical observed max number of satellites in SVNFO msg */ #define UBX_NAV_SVINFO_RX_PAYLOAD_SIZE (8 + 12 * UBX_MAX_NUM_SAT) /**< NAV_SVINFO Rx msg payload size */ /* CFG class Tx msg defs */ @@ -127,21 +127,21 @@ struct ubx_header { typedef struct { uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ - int32_t lon; /**< Longitude * 1e-7, deg */ - int32_t lat; /**< Latitude * 1e-7, deg */ - int32_t height; /**< Height above Ellipsoid, mm */ - int32_t height_msl; /**< Height above mean sea level, mm */ - uint32_t hAcc; /**< Horizontal Accuracy Estimate, mm */ - uint32_t vAcc; /**< Vertical Accuracy Estimate, mm */ + int32_t lon; /**< Longitude * 1e-7, deg */ + int32_t lat; /**< Latitude * 1e-7, deg */ + int32_t height; /**< Height above Ellipsoid, mm */ + int32_t height_msl; /**< Height above mean sea level, mm */ + uint32_t hAcc; /**< Horizontal Accuracy Estimate, mm */ + uint32_t vAcc; /**< Vertical Accuracy Estimate, mm */ uint8_t ck_a; uint8_t ck_b; } gps_bin_nav_posllh_packet_t; typedef struct { - uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ + uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ int32_t time_nanoseconds; /**< Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 */ - int16_t week; /**< GPS week (GPS time) */ - uint8_t gpsFix; /**< GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */ + int16_t week; /**< GPS week (GPS time) */ + uint8_t gpsFix; /**< GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */ uint8_t flags; int32_t ecefX; int32_t ecefY; @@ -153,7 +153,7 @@ typedef struct { uint32_t sAcc; uint16_t pDOP; uint8_t reserved1; - uint8_t numSV; /**< Number of SVs used in Nav Solution */ + uint8_t numSV; /**< Number of SVs used in Nav Solution */ uint32_t reserved2; uint8_t ck_a; uint8_t ck_b; @@ -163,47 +163,47 @@ typedef struct { uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ uint32_t time_accuracy; /**< Time Accuracy Estimate, ns */ int32_t time_nanoseconds; /**< Nanoseconds of second, range -1e9 .. 1e9 (UTC) */ - uint16_t year; /**< Year, range 1999..2099 (UTC) */ - uint8_t month; /**< Month, range 1..12 (UTC) */ - uint8_t day; /**< Day of Month, range 1..31 (UTC) */ - uint8_t hour; /**< Hour of Day, range 0..23 (UTC) */ - uint8_t min; /**< Minute of Hour, range 0..59 (UTC) */ - uint8_t sec; /**< Seconds of Minute, range 0..59 (UTC) */ + uint16_t year; /**< Year, range 1999..2099 (UTC) */ + uint8_t month; /**< Month, range 1..12 (UTC) */ + uint8_t day; /**< Day of Month, range 1..31 (UTC) */ + uint8_t hour; /**< Hour of Day, range 0..23 (UTC) */ + uint8_t min; /**< Minute of Hour, range 0..59 (UTC) */ + uint8_t sec; /**< Seconds of Minute, range 0..59 (UTC) */ uint8_t valid_flag; /**< Validity Flags (see ubx documentation) */ uint8_t ck_a; uint8_t ck_b; } gps_bin_nav_timeutc_packet_t; //typedef struct { -// uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ -// uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */ -// uint16_t pDOP; /**< Position DOP (scaling 0.01) */ -// uint16_t tDOP; /**< Time DOP (scaling 0.01) */ -// uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */ -// uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */ -// uint16_t nDOP; /**< Northing DOP (scaling 0.01) */ -// uint16_t eDOP; /**< Easting DOP (scaling 0.01) */ +// uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ +// uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */ +// uint16_t pDOP; /**< Position DOP (scaling 0.01) */ +// uint16_t tDOP; /**< Time DOP (scaling 0.01) */ +// uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */ +// uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */ +// uint16_t nDOP; /**< Northing DOP (scaling 0.01) */ +// uint16_t eDOP; /**< Easting DOP (scaling 0.01) */ // uint8_t ck_a; // uint8_t ck_b; //} gps_bin_nav_dop_packet_t; typedef struct { - uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ - uint8_t numCh; /**< Number of channels */ + uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ + uint8_t numCh; /**< Number of channels */ uint8_t globalFlags; uint16_t reserved2; } gps_bin_nav_svinfo_part1_packet_t; typedef struct { - uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */ - uint8_t svid; /**< Satellite ID */ + uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */ + uint8_t svid; /**< Satellite ID */ uint8_t flags; uint8_t quality; - uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength), dbHz */ - int8_t elev; /**< Elevation in integer degrees */ - int16_t azim; /**< Azimuth in integer degrees */ - int32_t prRes; /**< Pseudo range residual in centimetres */ + uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength), dbHz */ + int8_t elev; /**< Elevation in integer degrees */ + int16_t azim; /**< Azimuth in integer degrees */ + int32_t prRes; /**< Pseudo range residual in centimetres */ } gps_bin_nav_svinfo_part2_packet_t; @@ -268,8 +268,8 @@ struct gps_bin_mon_hw_ubx7_packet { //typedef struct { // int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */ -// int16_t week; /**< Measurement GPS week number */ -// uint8_t numVis; /**< Number of visible satellites */ +// int16_t week; /**< Measurement GPS week number */ +// uint8_t numVis; /**< Number of visible satellites */ // // //... rest of package is not used in this implementation // @@ -395,7 +395,7 @@ public: private: /** - * Parse the binary MTK packet + * Parse the binary UBX packet */ int parse_char(uint8_t b); -- cgit v1.2.3 From 9bad828bc0033c7017978de2321d3a8698c0afc6 Mon Sep 17 00:00:00 2001 From: Kynos Date: Fri, 30 May 2014 14:30:25 +0200 Subject: U-blox driver rework, step 2 Moved satellite info from vehicle_gps_position_s into a new uORB topic satellite_info. Renamed satellites_visible to satellites_used to reflect true content. sdlog2 will log info for GPS satellites only for now. --- src/drivers/blinkm/blinkm.cpp | 8 +-- src/drivers/gps/gps.cpp | 2 +- src/drivers/gps/mtk.cpp | 2 +- src/drivers/gps/ubx.cpp | 3 +- src/drivers/hott/messages.cpp | 2 +- src/modules/mavlink/mavlink_messages.cpp | 2 +- src/modules/mavlink/mavlink_receiver.cpp | 3 +- src/modules/sdlog2/sdlog2.c | 48 ++++++++------ src/modules/uORB/Subscription.cpp | 2 + src/modules/uORB/objects_common.cpp | 3 + src/modules/uORB/topics/satellite_info.h | 86 ++++++++++++++++++++++++++ src/modules/uORB/topics/vehicle_gps_position.h | 9 +-- 12 files changed, 130 insertions(+), 40 deletions(-) create mode 100644 src/modules/uORB/topics/satellite_info.h diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp index 5c502f682..39bf1fcfc 100644 --- a/src/drivers/blinkm/blinkm.cpp +++ b/src/drivers/blinkm/blinkm.cpp @@ -559,13 +559,7 @@ BlinkM::led() } /* get number of used satellites in navigation */ - num_of_used_sats = 0; - - for(unsigned satloop=0; satloopget_position_update_rate()); diff --git a/src/drivers/gps/mtk.cpp b/src/drivers/gps/mtk.cpp index 680f00d97..7b957e55d 100644 --- a/src/drivers/gps/mtk.cpp +++ b/src/drivers/gps/mtk.cpp @@ -263,7 +263,7 @@ MTK::handle_message(gps_mtk_packet_t &packet) _gps_position->epv_m = _gps_position->eph_m; // unknown in mtk custom mode, so we cheat with eph _gps_position->vel_m_s = ((float)packet.ground_speed) * 1e-2f; // from cm/s to m/s _gps_position->cog_rad = ((float)packet.heading) * M_DEG_TO_RAD_F * 1e-2f; //from deg *100 to rad - _gps_position->satellites_visible = packet.satellites; + _gps_position->satellites_used = packet.satellites; /* convert time and date information to unix timestamp */ struct tm timeinfo; //TODO: test this conversion diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index d7e9454ae..462875b6c 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -55,6 +55,7 @@ #include #include #include +#include #include #include "ubx.h" @@ -451,7 +452,7 @@ UBX::handle_message() _gps_position->s_variance_m_s = packet->sAcc; _gps_position->p_variance_m = packet->pAcc; _gps_position->timestamp_variance = hrt_absolute_time(); - _gps_position->satellites_visible = packet->numSV; + _gps_position->satellites_used = packet->numSV; ret = 1; break; diff --git a/src/drivers/hott/messages.cpp b/src/drivers/hott/messages.cpp index 1e779e8dc..086132573 100644 --- a/src/drivers/hott/messages.cpp +++ b/src/drivers/hott/messages.cpp @@ -226,7 +226,7 @@ build_gps_response(uint8_t *buffer, size_t *size) msg.sensor_id = GPS_SENSOR_ID; msg.sensor_text_id = GPS_SENSOR_TEXT_ID; - msg.gps_num_sat = gps.satellites_visible; + msg.gps_num_sat = gps.satellites_used; /* The GPS fix type: 0 = none, 2 = 2D, 3 = 3D */ msg.gps_fix_char = (uint8_t)(gps.fix_type + 48); diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 933478f56..146e2d4b8 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -548,7 +548,7 @@ protected: cm_uint16_from_m_float(gps->epv_m), gps->vel_m_s * 100.0f, _wrap_2pi(gps->cog_rad) * M_RAD_TO_DEG_F * 1e2f, - gps->satellites_visible); + gps->satellites_used); } } }; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 53769e0cf..46da1a0be 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -682,9 +682,8 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg) hil_gps.vel_ned_valid = true; hil_gps.cog_rad = _wrap_pi(gps.cog * M_DEG_TO_RAD_F * 1e-2f); - hil_gps.timestamp_satellites = timestamp; hil_gps.fix_type = gps.fix_type; - hil_gps.satellites_visible = gps.satellites_visible; + hil_gps.satellites_used = gps.satellites_visible; //TODO: rename mavlink_hil_gps_t sats visible to used? if (_gps_pub < 0) { _gps_pub = orb_advertise(ORB_ID(vehicle_gps_position), &hil_gps); diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 577cadfbb..4ff6c30aa 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -74,6 +74,7 @@ #include #include #include +#include #include #include #include @@ -139,6 +140,8 @@ PARAM_DEFINE_INT32(SDLOG_EXT, -1); fds[fdsc_count].events = POLLIN; \ fdsc_count++; +#define MIN(X,Y) ((X) < (Y) ? (X) : (Y)) + static bool main_thread_should_exit = false; /**< Deamon exit flag */ static bool thread_running = false; /**< Deamon status flag */ static int deamon_task; /**< Handle of deamon task / thread */ @@ -941,6 +944,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct estimator_status_report estimator_status; struct system_power_s system_power; struct servorail_status_s servorail_status; + struct satellite_info_s sat_info; } buf; memset(&buf, 0, sizeof(buf)); @@ -1000,6 +1004,7 @@ int sdlog2_thread_main(int argc, char *argv[]) int global_pos_sub; int triplet_sub; int gps_pos_sub; + int sat_info_sub; int vicon_pos_sub; int flow_sub; int rc_sub; @@ -1017,6 +1022,7 @@ int sdlog2_thread_main(int argc, char *argv[]) subs.cmd_sub = orb_subscribe(ORB_ID(vehicle_command)); subs.status_sub = orb_subscribe(ORB_ID(vehicle_status)); subs.gps_pos_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); + subs.sat_info_sub = orb_subscribe(ORB_ID(satellite_info)); subs.sensor_sub = orb_subscribe(ORB_ID(sensor_combined)); subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); @@ -1053,6 +1059,9 @@ int sdlog2_thread_main(int argc, char *argv[]) hrt_abstime barometer_timestamp = 0; hrt_abstime differential_pressure_timestamp = 0; + /* initialize calculated mean SNR */ + float snr_mean = 0.0f; + /* enable logging on start if needed */ if (log_on_start) { /* check GPS topic to get GPS time */ @@ -1115,14 +1124,6 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- GPS POSITION - UNIT #1 --- */ if (gps_pos_updated) { - float snr_mean = 0.0f; - - for (unsigned i = 0; i < buf_gps_pos.satellites_visible; i++) { - snr_mean += buf_gps_pos.satellite_snr[i]; - } - - snr_mean /= buf_gps_pos.satellites_visible; - log_msg.msg_type = LOG_GPS_MSG; log_msg.body.log_GPS.gps_time = buf_gps_pos.time_gps_usec; log_msg.body.log_GPS.fix_type = buf_gps_pos.fix_type; @@ -1135,44 +1136,55 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.body.log_GPS.vel_e = buf_gps_pos.vel_e_m_s; log_msg.body.log_GPS.vel_d = buf_gps_pos.vel_d_m_s; log_msg.body.log_GPS.cog = buf_gps_pos.cog_rad; - log_msg.body.log_GPS.sats = buf_gps_pos.satellites_visible; + log_msg.body.log_GPS.sats = buf_gps_pos.satellites_used; log_msg.body.log_GPS.snr_mean = snr_mean; log_msg.body.log_GPS.noise_per_ms = buf_gps_pos.noise_per_ms; log_msg.body.log_GPS.jamming_indicator = buf_gps_pos.jamming_indicator; LOGBUFFER_WRITE_AND_COUNT(GPS); + } + + /* --- SATELLITE INFO - UNIT #1 --- */ + if (_extended_logging) { + + if (copy_if_updated(ORB_ID(satellite_info), subs.sat_info_sub, &buf.sat_info)) { - if (_extended_logging) { /* log the SNR of each satellite for a detailed view of signal quality */ - unsigned gps_msg_max_snr = sizeof(buf_gps_pos.satellite_snr) / sizeof(buf_gps_pos.satellite_snr[0]); + unsigned sat_info_count = MIN(buf.sat_info.count, sizeof(buf.sat_info.snr) / sizeof(buf.sat_info.snr[0])); unsigned log_max_snr = sizeof(log_msg.body.log_GS0A.satellite_snr) / sizeof(log_msg.body.log_GS0A.satellite_snr[0]); log_msg.msg_type = LOG_GS0A_MSG; memset(&log_msg.body.log_GS0A, 0, sizeof(log_msg.body.log_GS0A)); - /* fill set A */ - for (unsigned i = 0; i < gps_msg_max_snr; i++) { + snr_mean = 0.0f; - int satindex = buf_gps_pos.satellite_prn[i] - 1; + /* fill set A and calculate mean SNR */ + for (unsigned i = 0; i < sat_info_count; i++) { + + snr_mean += buf.sat_info.snr[i]; + + int satindex = buf.sat_info.svid[i] - 1; /* handles index exceeding and wraps to to arithmetic errors */ if ((satindex >= 0) && (satindex < (int)log_max_snr)) { /* map satellites by their ID so that logs from two receivers can be compared */ - log_msg.body.log_GS0A.satellite_snr[satindex] = buf_gps_pos.satellite_snr[i]; + log_msg.body.log_GS0A.satellite_snr[satindex] = buf.sat_info.snr[i]; } } LOGBUFFER_WRITE_AND_COUNT(GS0A); + snr_mean /= sat_info_count; log_msg.msg_type = LOG_GS0B_MSG; memset(&log_msg.body.log_GS0B, 0, sizeof(log_msg.body.log_GS0B)); + /* fill set B */ - for (unsigned i = 0; i < gps_msg_max_snr; i++) { + for (unsigned i = 0; i < sat_info_count; i++) { /* get second bank of satellites, thus deduct bank size from index */ - int satindex = buf_gps_pos.satellite_prn[i] - 1 - log_max_snr; + int satindex = buf.sat_info.svid[i] - 1 - log_max_snr; /* handles index exceeding and wraps to to arithmetic errors */ if ((satindex >= 0) && (satindex < (int)log_max_snr)) { /* map satellites by their ID so that logs from two receivers can be compared */ - log_msg.body.log_GS0B.satellite_snr[satindex] = buf_gps_pos.satellite_snr[i]; + log_msg.body.log_GS0B.satellite_snr[satindex] = buf.sat_info.snr[i]; } } LOGBUFFER_WRITE_AND_COUNT(GS0B); diff --git a/src/modules/uORB/Subscription.cpp b/src/modules/uORB/Subscription.cpp index c1d1a938f..44b6debc7 100644 --- a/src/modules/uORB/Subscription.cpp +++ b/src/modules/uORB/Subscription.cpp @@ -40,6 +40,7 @@ #include "topics/parameter_update.h" #include "topics/actuator_controls.h" #include "topics/vehicle_gps_position.h" +#include "topics/satellite_info.h" #include "topics/sensor_combined.h" #include "topics/vehicle_attitude.h" #include "topics/vehicle_global_position.h" @@ -88,6 +89,7 @@ T Subscription::getData() { template class __EXPORT Subscription; template class __EXPORT Subscription; template class __EXPORT Subscription; +template class __EXPORT Subscription; template class __EXPORT Subscription; template class __EXPORT Subscription; template class __EXPORT Subscription; diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp index 90675bb2e..fc12b9ed5 100644 --- a/src/modules/uORB/objects_common.cpp +++ b/src/modules/uORB/objects_common.cpp @@ -75,6 +75,9 @@ ORB_DEFINE(sensor_combined, struct sensor_combined_s); #include "topics/vehicle_gps_position.h" ORB_DEFINE(vehicle_gps_position, struct vehicle_gps_position_s); +#include "topics/satellite_info.h" +ORB_DEFINE(satellite_info, struct satellite_info_s); + #include "topics/home_position.h" ORB_DEFINE(home_position, struct home_position_s); diff --git a/src/modules/uORB/topics/satellite_info.h b/src/modules/uORB/topics/satellite_info.h new file mode 100644 index 000000000..5f799eda4 --- /dev/null +++ b/src/modules/uORB/topics/satellite_info.h @@ -0,0 +1,86 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * Author: @author Thomas Gubler + * @author Julian Oes + * @author Lorenz Meier + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file satellite_info.h + * Definition of the GNSS satellite info uORB topic. + */ + +#ifndef TOPIC_SAT_INFO_H_ +#define TOPIC_SAT_INFO_H_ + +#include +#include "../uORB.h" + +/** + * @addtogroup topics + * @{ + */ + +/** + * GNSS Satellite Info. + */ +struct satellite_info_s { + uint64_t timestamp; /**< Timestamp of satellite information */ + uint8_t count; /**< Number of satellites in satellite_...[] arrays */ + uint8_t svid[20]; /**< Space vehicle ID [1..255], see scheme below */ + uint8_t used[20]; /**< 0: Satellite not used, 1: used for navigation */ + uint8_t elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ + uint8_t azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */ + uint8_t snr[20]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */ +}; + +/** + * NAV_SVINFO space vehicle ID (svid) scheme according to u-blox protocol specs + * u-bloxM8-V15_ReceiverDescriptionProtocolSpec_Public_(UBX-13003221).pdf + * + * GPS 1-32 + * SBAS 120-158 + * Galileo 211-246 + * BeiDou 159-163, 33-64 + * QZSS 193-197 + * GLONASS 65-96, 255 + * + */ + +/** + * @} + */ + +/* register this as object request broker structure */ +ORB_DECLARE(satellite_info); + +#endif diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h index 5924a324d..a50f02139 100644 --- a/src/modules/uORB/topics/vehicle_gps_position.h +++ b/src/modules/uORB/topics/vehicle_gps_position.h @@ -82,14 +82,7 @@ struct vehicle_gps_position_s { uint64_t timestamp_time; /**< Timestamp for time information */ uint64_t time_gps_usec; /**< Timestamp (microseconds in GPS format), this is the timestamp which comes from the gps module */ - uint64_t timestamp_satellites; /**< Timestamp for sattelite information */ - uint8_t satellites_visible; /**< Number of satellites visible. If unknown, set to 255 */ - uint8_t satellite_prn[20]; /**< Global satellite ID */ - uint8_t satellite_used[20]; /**< 0: Satellite not used, 1: used for localization */ - uint8_t satellite_elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ - uint8_t satellite_azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */ - uint8_t satellite_snr[20]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */ - bool satellite_info_available; /**< 0 for no info, 1 for info available */ + uint8_t satellites_used; /**< Number of satellites used */ }; /** -- cgit v1.2.3 From 5c536ae46ec44b75fea745dd79f20b0aef2c8f16 Mon Sep 17 00:00:00 2001 From: Benjamin O'Connell-Armand Date: Mon, 2 Jun 2014 23:10:03 -0400 Subject: Added processing of postion_control offboard messages (quad_swarm) --- src/modules/mavlink/mavlink_receiver.cpp | 17 ++++++++++++++++- src/modules/mavlink/mavlink_receiver.h | 1 + 2 files changed, 17 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 561744755..78c50c422 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -102,6 +102,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) : _cmd_pub(-1), _flow_pub(-1), _offboard_control_sp_pub(-1), + _local_pos_sp_pub(-1), _att_sp_pub(-1), _rates_sp_pub(-1), _vicon_position_pub(-1), @@ -411,7 +412,21 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message if (_control_mode.flag_control_offboard_enabled) { if (_control_mode.flag_control_position_enabled) { - // TODO + // TODO Use something else then quad_swarm_roll_pitch_yaw_thrust + struct vehicle_local_position_setpoint_s loc_pos_sp; + memset(&loc_pos_sp, 0, sizeof(loc_pos_sp)); + + loc_pos_sp.x = offboard_control_sp.p1; + loc_pos_sp.y = offboard_control_sp.p2; + loc_pos_sp.yaw = offboard_control_sp.p3; + loc_pos_sp.z = offboard_control_sp.p4; + + if (_local_pos_sp_pub < 0) { + _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp_pub); + + } else { + orb_publish(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_pub, &loc_pos_sp); + } } else if (_control_mode.flag_control_velocity_enabled) { // TODO diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index dc31b4c5a..a2736969f 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -137,6 +137,7 @@ private: orb_advert_t _cmd_pub; orb_advert_t _flow_pub; orb_advert_t _offboard_control_sp_pub; + orb_advert_t _local_pos_sp_pub orb_advert_t _att_sp_pub; orb_advert_t _rates_sp_pub; orb_advert_t _vicon_position_pub; -- cgit v1.2.3 From 1fc859b1b195b587e70e4a8f6fbeb952424d0610 Mon Sep 17 00:00:00 2001 From: Benjamin O'Connell-Armand Date: Mon, 2 Jun 2014 23:11:31 -0400 Subject: Added support for postion_control offboard messages in commander. --- src/modules/commander/commander.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 90efd5115..29a5f0b4a 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1809,6 +1809,14 @@ set_control_mode() control_mode.flag_control_offboard_enabled = true; switch (sp_offboard.mode) { + case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: + control_mode.flag_control_rates_enabled = false; + control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_position_enabled = true; + control_mode.flag_control_velocity_enabled = false; + break; case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: control_mode.flag_control_rates_enabled = true; control_mode.flag_control_attitude_enabled = true; -- cgit v1.2.3 From 882076a0d48d465becff9c62db0096e76dd685b3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 3 Jun 2014 16:38:45 +0200 Subject: Better defaults for min values for some of the multicopters --- ROMFS/px4fmu_common/init.d/10016_3dr_iris | 3 +++ ROMFS/px4fmu_common/init.d/4010_dji_f330 | 4 ++-- ROMFS/px4fmu_common/init.d/4011_dji_f450 | 4 ++-- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/10016_3dr_iris b/ROMFS/px4fmu_common/init.d/10016_3dr_iris index 084dff140..3f47390c1 100644 --- a/ROMFS/px4fmu_common/init.d/10016_3dr_iris +++ b/ROMFS/px4fmu_common/init.d/10016_3dr_iris @@ -30,3 +30,6 @@ fi set MIXER FMU_quad_w set PWM_OUTPUTS 1234 + +set PWM_MIN 1200 +set PWM_MAX 1950 diff --git a/ROMFS/px4fmu_common/init.d/4010_dji_f330 b/ROMFS/px4fmu_common/init.d/4010_dji_f330 index cd4480c3e..aa4394015 100644 --- a/ROMFS/px4fmu_common/init.d/4010_dji_f330 +++ b/ROMFS/px4fmu_common/init.d/4010_dji_f330 @@ -23,5 +23,5 @@ then param set MC_YAWRATE_D 0.0 fi -set PWM_MIN 1175 -set PWM_MAX 1900 +set PWM_MIN 1200 +set PWM_MAX 1950 diff --git a/ROMFS/px4fmu_common/init.d/4011_dji_f450 b/ROMFS/px4fmu_common/init.d/4011_dji_f450 index ac2ecc70a..4d055b421 100644 --- a/ROMFS/px4fmu_common/init.d/4011_dji_f450 +++ b/ROMFS/px4fmu_common/init.d/4011_dji_f450 @@ -24,5 +24,5 @@ then param set MC_YAWRATE_D 0.0 fi -set PWM_MIN 1175 -set PWM_MAX 1900 +set PWM_MIN 1230 +set PWM_MAX 1950 -- cgit v1.2.3 From 55cf19b0826911c88ca1f62f90e4d1c7e9ddf2b2 Mon Sep 17 00:00:00 2001 From: andre-nguyen Date: Tue, 3 Jun 2014 21:45:29 -0400 Subject: added support for offboard position setpoint in mc_pos_control --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 09960d106..d870b733f 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -118,6 +118,7 @@ private: int _arming_sub; /**< arming status of outputs */ int _local_pos_sub; /**< vehicle local position */ int _pos_sp_triplet_sub; /**< position setpoint triplet */ + int _offboard_control_pos_sp_sub; /**< offboard control position setpoint */ orb_advert_t _att_sp_pub; /**< attitude setpoint publication */ orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */ @@ -132,6 +133,8 @@ private: struct position_setpoint_triplet_s _pos_sp_triplet; /**< vehicle global position setpoint triplet */ struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position setpoint */ struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */ + struct offboard_control_setpoint_s _offboard_control_pos_sp; /**< offboard control position setpoint + struct { param_t thr_min; @@ -277,6 +280,7 @@ MulticopterPositionControl::MulticopterPositionControl() : memset(&_pos_sp_triplet, 0, sizeof(_pos_sp_triplet)); memset(&_local_pos_sp, 0, sizeof(_local_pos_sp)); memset(&_global_vel_sp, 0, sizeof(_global_vel_sp)); + memset(&_offboard_control_pos_sp, 0, sizeof(_offboard_control_pos_sp)); memset(&_ref_pos, 0, sizeof(_ref_pos)); @@ -528,6 +532,7 @@ MulticopterPositionControl::task_main() _arming_sub = orb_subscribe(ORB_ID(actuator_armed)); _local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); _pos_sp_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet)); + _offboard_control_pos_sp_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); parameters_update(true); @@ -664,6 +669,23 @@ MulticopterPositionControl::task_main() _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max); } + } else if (_control_mode.flag_control_offboard_enabled) { + /* Offboard control */ + /* Team elikos doesn't really know what it is doing */ + bool updated; + orb_check(_offboard_control_pos_sp_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(offboard_control_setpoint), _offboard_control_pos_sp_sub, + &_offboard_control_pos_sp); + } + + /* Hopefully no one dies from this */ + pos(0) = _offboard_control_pos_sp.p1; + pos(1) = _offboard_control_pos_sp.p2; + pos(2) = _offboard_control_pos_sp.p4; + _att_sp.yaw_body = _offboard_control_pos_sp.p3; + } else { /* AUTO */ bool updated; -- cgit v1.2.3 From ce1251fcc8119b2c4e8c9a3b5e7f0e0104fc975f Mon Sep 17 00:00:00 2001 From: Benjamin O'Connell-Armand Date: Tue, 3 Jun 2014 22:30:14 -0400 Subject: Quick fix --- src/modules/mavlink/mavlink_receiver.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index a2736969f..db9e06461 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -137,7 +137,7 @@ private: orb_advert_t _cmd_pub; orb_advert_t _flow_pub; orb_advert_t _offboard_control_sp_pub; - orb_advert_t _local_pos_sp_pub + orb_advert_t _local_pos_sp_pub; orb_advert_t _att_sp_pub; orb_advert_t _rates_sp_pub; orb_advert_t _vicon_position_pub; -- cgit v1.2.3 From e12d3af503c5ebc105e5b3c3ef8e51bd75959329 Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Tue, 3 Jun 2014 23:38:18 -0400 Subject: Added support for offboard velocity control & fixed position control flags --- src/modules/commander/commander.cpp | 22 +++++++++++++++------- 1 file changed, 15 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 29a5f0b4a..3da43a792 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1809,12 +1809,12 @@ set_control_mode() control_mode.flag_control_offboard_enabled = true; switch (sp_offboard.mode) { - case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: - control_mode.flag_control_rates_enabled = false; + case OFFBOARD_CONTROL_MODE_DIRECT_RATES: + control_mode.flag_control_rates_enabled = true; control_mode.flag_control_attitude_enabled = false; control_mode.flag_control_altitude_enabled = false; control_mode.flag_control_climb_rate_enabled = false; - control_mode.flag_control_position_enabled = true; + control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; break; case OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE: @@ -1825,13 +1825,21 @@ set_control_mode() control_mode.flag_control_position_enabled = false; control_mode.flag_control_velocity_enabled = false; break; - case OFFBOARD_CONTROL_MODE_DIRECT_RATES: + case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY: control_mode.flag_control_rates_enabled = true; - control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_attitude_enabled = true; control_mode.flag_control_altitude_enabled = false; - control_mode.flag_control_climb_rate_enabled = false; + control_mode.flag_control_climb_rate_enabled = true; control_mode.flag_control_position_enabled = false; - control_mode.flag_control_velocity_enabled = false; + control_mode.flag_control_velocity_enabled = true; + break; + case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: + control_mode.flag_control_rates_enabled = true; + control_mode.flag_control_attitude_enabled = true; + control_mode.flag_control_altitude_enabled = true; + control_mode.flag_control_climb_rate_enabled = true; + control_mode.flag_control_position_enabled = true; + control_mode.flag_control_velocity_enabled = true; break; default: control_mode.flag_control_rates_enabled = false; -- cgit v1.2.3 From f1b6a3f44f3c1ade07de2a1a996b055eccd5155c Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Tue, 3 Jun 2014 23:55:21 -0400 Subject: Fixed offboard_control_pos_sp to be passed to _pos_sp vector. Added checks for position and altitude control modes. --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index d870b733f..b2693345c 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -681,9 +681,16 @@ MulticopterPositionControl::task_main() } /* Hopefully no one dies from this */ - pos(0) = _offboard_control_pos_sp.p1; - pos(1) = _offboard_control_pos_sp.p2; - pos(2) = _offboard_control_pos_sp.p4; + /* Make sure position control is selected i.e. not only velocity control */ + if (_control_mode.flag_control_position_enabled) { + _pos_sp(0) = _offboard_control_pos_sp.p1; + _pos_sp(1) = _offboard_control_pos_sp.p2; + } + + if (_control_mode.flag_control_altitude_enabled) { + _pos_sp(2) = _offboard_control_pos_sp.p4; + } + _att_sp.yaw_body = _offboard_control_pos_sp.p3; } else { -- cgit v1.2.3 From abbf57dac655bb0832052efea9841b7e41525799 Mon Sep 17 00:00:00 2001 From: andre-nguyen Date: Wed, 4 Jun 2014 00:04:31 -0400 Subject: had the wrong variable and wrong setpoint type --- src/modules/mavlink/mavlink_receiver.cpp | 1 + src/modules/mc_pos_control/mc_pos_control_main.cpp | 14 +++++++------- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 78c50c422..2157ae00b 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -379,6 +379,7 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message case 4: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION; + ml_armed = true; break; default: break; diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index d870b733f..4d0c3216a 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -133,7 +133,7 @@ private: struct position_setpoint_triplet_s _pos_sp_triplet; /**< vehicle global position setpoint triplet */ struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position setpoint */ struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */ - struct offboard_control_setpoint_s _offboard_control_pos_sp; /**< offboard control position setpoint + struct vehicle_local_position_setpoint_s _offboard_control_pos_sp; /**< offboard control position setpoint */ struct { @@ -532,7 +532,7 @@ MulticopterPositionControl::task_main() _arming_sub = orb_subscribe(ORB_ID(actuator_armed)); _local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); _pos_sp_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet)); - _offboard_control_pos_sp_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); + _offboard_control_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); parameters_update(true); @@ -676,15 +676,15 @@ MulticopterPositionControl::task_main() orb_check(_offboard_control_pos_sp_sub, &updated); if (updated) { - orb_copy(ORB_ID(offboard_control_setpoint), _offboard_control_pos_sp_sub, + orb_copy(ORB_ID(vehicle_local_position_setpoint), _offboard_control_pos_sp_sub, &_offboard_control_pos_sp); } /* Hopefully no one dies from this */ - pos(0) = _offboard_control_pos_sp.p1; - pos(1) = _offboard_control_pos_sp.p2; - pos(2) = _offboard_control_pos_sp.p4; - _att_sp.yaw_body = _offboard_control_pos_sp.p3; + _pos_sp(0) = _offboard_control_pos_sp.x; + _pos_sp(1) = _offboard_control_pos_sp.y; + _pos_sp(2) = _offboard_control_pos_sp.z; + _att_sp.yaw_body = _offboard_control_pos_sp.yaw; } else { /* AUTO */ -- cgit v1.2.3 From af56879fdd94c1b712657e071324b3a6f147caa7 Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Wed, 4 Jun 2014 02:32:44 -0400 Subject: Removed duplicate _pos_sp assignation --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index b73becf3c..87a8385d3 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -680,12 +680,6 @@ MulticopterPositionControl::task_main() &_offboard_control_pos_sp); } - /* Hopefully no one dies from this */ - _pos_sp(0) = _offboard_control_pos_sp.x; - _pos_sp(1) = _offboard_control_pos_sp.y; - _pos_sp(2) = _offboard_control_pos_sp.z; - _att_sp.yaw_body = _offboard_control_pos_sp.yaw; - /* Make sure position control is selected i.e. not only velocity control */ if (_control_mode.flag_control_position_enabled) { _pos_sp(0) = _offboard_control_pos_sp.x; -- cgit v1.2.3 From c4280a7cd83f7793d4773ffedd36e0fa220e2c07 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 6 Jun 2014 17:47:25 +0200 Subject: matlab logging: Initial CSV example --- src/examples/matlab_csv_serial/matlab_csv_serial.c | 246 +++++++++++++++++++++ src/examples/matlab_csv_serial/module.mk | 41 ++++ 2 files changed, 287 insertions(+) create mode 100644 src/examples/matlab_csv_serial/matlab_csv_serial.c create mode 100644 src/examples/matlab_csv_serial/module.mk diff --git a/src/examples/matlab_csv_serial/matlab_csv_serial.c b/src/examples/matlab_csv_serial/matlab_csv_serial.c new file mode 100644 index 000000000..7c8bcc31e --- /dev/null +++ b/src/examples/matlab_csv_serial/matlab_csv_serial.c @@ -0,0 +1,246 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file matlab_csv_serial_main.c + * + * Matlab CSV / ASCII format interface at 921600 baud, 8 data bits, + * 1 stop bit, no parity + * + * @author Lorenz Meier + */ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +__EXPORT int matlab_csv_serial_main(int argc, char *argv[]); +static bool thread_should_exit = false; /**< Daemon exit flag */ +static bool thread_running = false; /**< Daemon status flag */ +static int daemon_task; /**< Handle of daemon task / thread */ + +int matlab_csv_serial_thread_main(int argc, char *argv[]); +static void usage(const char *reason); + +static void usage(const char *reason) +{ + if (reason) + fprintf(stderr, "%s\n", reason); + fprintf(stderr, "usage: daemon {start|stop|status} [-p ]\n\n"); + exit(1); +} + +/** + * The daemon app only briefly exists to start + * the background job. The stack size assigned in the + * Makefile does only apply to this management task. + * + * The actual stack size should be set in the call + * to task_spawn_cmd(). + */ +int matlab_csv_serial_main(int argc, char *argv[]) +{ + if (argc < 1) + usage("missing command"); + + if (!strcmp(argv[1], "start")) + { + if (thread_running) + { + printf("flow position estimator already running\n"); + /* this is not an error */ + exit(0); + } + + thread_should_exit = false; + daemon_task = task_spawn_cmd("matlab_csv_serial", + SCHED_DEFAULT, + SCHED_PRIORITY_MAX - 5, + 2000, + matlab_csv_serial_thread_main, + (argv) ? (const char **)&argv[2] : (const char **)NULL); + exit(0); + } + + if (!strcmp(argv[1], "stop")) + { + thread_should_exit = true; + exit(0); + } + + if (!strcmp(argv[1], "status")) + { + if (thread_running) { + warnx("running"); + } else { + warnx("stopped"); + } + + exit(0); + } + + usage("unrecognized command"); + exit(1); +} + +int matlab_csv_serial_thread_main(int argc, char *argv[]) +{ + /* welcome user */ + thread_running = true; + + if (argc < 2) { + errx(1, "need a serial port name as argument"); + } + + int serial_fd = open(argv[1], O_RDWR | O_NOCTTY); + + unsigned speed = 921600; + + if (serial_fd < 0) { + err(1, "failed to open port: %s", argv[1]); + } + + /* Try to set baud rate */ + struct termios uart_config; + int termios_state; + bool is_usb = false; + + /* Back up the original uart configuration to restore it after exit */ + if ((termios_state = tcgetattr(_uart_fd, uart_config_original)) < 0) { + warnx("ERR GET CONF %s: %d\n", uart_name, termios_state); + close(_uart_fd); + return -1; + } + + /* Fill the struct for the new configuration */ + tcgetattr(_uart_fd, &uart_config); + + /* Clear ONLCR flag (which appends a CR for every LF) */ + uart_config.c_oflag &= ~ONLCR; + + /* USB serial is indicated by /dev/ttyACM0*/ + if (strcmp(uart_name, "/dev/ttyACM0") != OK && strcmp(uart_name, "/dev/ttyACM1") != OK) { + + /* Set baud rate */ + if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { + warnx("ERR SET BAUD %s: %d\n", argv[1], termios_state); + close(serial_fd); + return -1; + } + + } + + if ((termios_state = tcsetattr(serial_fd, TCSANOW, &uart_config)) < 0) { + warnx("ERR SET CONF %s\n", argv[1]); + close(serial_fd); + return -1; + } + + /* subscribe to vehicle status, attitude, sensors and flow*/ + struct accel_report accel0; + struct accel_report accel1; + struct gyro_report gyro0; + struct gyro_report gyro1; + + /* subscribe to parameter changes */ + int accel0_sub = orb_subscribe(ORB_ID(sensor_accel)); + int accel1_sub; + int gyro0_sub; + int gyro1_sub; + + while (!thread_should_exit) + { + + /*This runs at the rate of the sensors */ + struct pollfd fds[] = { + { .fd = accel0_sub, .events = POLLIN }, + { .fd = accel1_sub, .events = POLLIN }, + { .fd = gyro0_sub, .events = POLLIN }, + { .fd = gyro1_sub, .events = POLLIN } + }; + + /* wait for a sensor update, check for exit condition every 500 ms */ + int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), 500); + + if (ret < 0) + { + /* poll error, count it in perf */ + perf_count(mc_err_perf); + + } + else if (ret == 0) + { + /* no return value, ignore */ + warnx("no sensor data"); + } + else + { + + /* parameter update available? */ + if (fds[0].revents & POLLIN) + { + orb_copy(ORB_ID(sensor_accel), accel0_sub, &accel0); + + // write out on accel 0, but collect for all other sensors as they have updates + vdprintf(serial_fd, "%llu,%d\n", accel0.timestamp, (int)accel0.x_raw); + } + + } + } + + warnx("exiting"); + thread_running = false; + + fflush(stdout); + return 0; +} + + diff --git a/src/examples/matlab_csv_serial/module.mk b/src/examples/matlab_csv_serial/module.mk new file mode 100644 index 000000000..c83d1fefd --- /dev/null +++ b/src/examples/matlab_csv_serial/module.mk @@ -0,0 +1,41 @@ +############################################################################ +# +# Copyright (c) 2014 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# Build position estimator +# + +MODULE_COMMAND = matlab_csv_serial + +SRCS = matlab_csv_serial.c \ + matlab_csv_serial.c -- cgit v1.2.3 From 2a79a9a4e4ebae2e85dab64ae98ff2a17e421ea2 Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Thu, 5 Jun 2014 04:03:40 -0400 Subject: Close fds when not needed File descriptors get closed when not needed by offboard mode to allow position and attitude controllers to advertise and publish. --- src/modules/mavlink/mavlink_receiver.cpp | 39 ++++++++++++++++++++++ src/modules/mc_att_control/mc_att_control_main.cpp | 8 ++++- src/modules/mc_pos_control/mc_pos_control_main.cpp | 8 ++++- 3 files changed, 53 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 2157ae00b..3b3423a4b 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -422,6 +422,17 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message loc_pos_sp.yaw = offboard_control_sp.p3; loc_pos_sp.z = offboard_control_sp.p4; + /* Close fds to allow position controller to use attitude controller */ + if (_att_sp_pub > 0) { + close(_att_sp_pub); + _att_sp_pub = -1; + } + + if (_rates_sp_pub > 0) { + close(_rates_sp_pub); + _rates_sp_pub = -1; + } + if (_local_pos_sp_pub < 0) { _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp_pub); @@ -444,6 +455,12 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message att_sp.timestamp = hrt_absolute_time(); + /* Close fd to allow attitude controller to publish its own rates sp*/ + if (_rates_sp_pub > 0) { + close(_rates_sp_pub); + _rates_sp_pub = -1; + } + if (_att_sp_pub < 0) { _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); @@ -993,6 +1010,28 @@ MavlinkReceiver::receive_thread(void *arg) } } } + /* Close unused fds when not in offboard mode anymore */ + bool updated; + orb_check(_control_mode_sub, &updated); + if (updated) { + orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); + if (!_control_mode.flag_control_offboard_enabled) { + if (_local_pos_sp_pub > 0) { + close(_local_pos_sp_pub); + _local_pos_sp_pub = -1; + } + + if (_att_sp_pub > 0) { + close(_att_sp_pub); + _att_sp_pub = -1; + } + + if (_rates_sp_pub > 0) { + close(_rates_sp_pub); + _rates_sp_pub = -1; + } + } + } } return NULL; diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 20e016da3..26c0c386f 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -584,9 +584,15 @@ MulticopterAttitudeControl::control_attitude(float dt) if (_att_sp_pub > 0) { orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_v_att_sp); - } else { + } else if (!_v_control_mode.flag_control_offboard_enabled) { _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_v_att_sp); } + + /* Close fd to let offboard att sp be advertised in mavlink receiver*/ + if (_v_control_mode.flag_control_offboard_enabled && _att_sp_pub > 0) { + close(_att_sp_pub); + _att_sp_pub = -1; + } } /* rotation matrix for current state */ diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 87a8385d3..4ee78516f 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -734,10 +734,16 @@ MulticopterPositionControl::task_main() if (_local_pos_sp_pub > 0) { orb_publish(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_pub, &_local_pos_sp); - } else { + } else if (!_control_mode.flag_control_offboard_enabled) { _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp); } + /* Close fd to let offboard pos sp be advertised in mavlink receiver*/ + if (_control_mode.flag_control_offboard_enabled && _local_pos_sp_pub > 0) { + close(_local_pos_sp_pub); + _local_pos_sp_pub = -1; + } + if (!_control_mode.flag_control_manual_enabled && _pos_sp_triplet.current.valid && _pos_sp_triplet.current.type == SETPOINT_TYPE_IDLE) { /* idle state, don't run controller and set zero thrust */ R.identity(); -- cgit v1.2.3 From 9f754e0e9a2e2ad75a3fe5a15690cf542ce08e8a Mon Sep 17 00:00:00 2001 From: Kynos Date: Sun, 8 Jun 2014 14:05:35 +0200 Subject: U-blox driver rework, step 3 More sat info isolation Flush input after changing baudrate to allow driver restart w/o GNSS module restart --- src/drivers/gps/gps.cpp | 98 ++++++++++++++----------- src/drivers/gps/ubx.cpp | 119 ++++++++++++++----------------- src/drivers/gps/ubx.h | 10 +-- src/modules/uORB/topics/satellite_info.h | 17 +++-- 4 files changed, 126 insertions(+), 118 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index d2ffc30ba..d8e2bd797 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -63,6 +63,7 @@ #include #include #include +#include #include @@ -106,8 +107,10 @@ private: bool _mode_changed; ///< flag that the GPS mode has changed gps_driver_mode_t _mode; ///< current mode GPS_Helper *_Helper; ///< instance of GPS parser - struct vehicle_gps_position_s _report; ///< uORB topic for gps position - orb_advert_t _report_pub; ///< uORB pub for gps position + struct vehicle_gps_position_s _report_gps_pos; ///< uORB topic for gps position + orb_advert_t _report_gps_pos_pub; ///< uORB pub for gps position + struct satellite_info_s _report_sat_info; ///< uORB topic for satellite info + orb_advert_t _report_sat_info_pub; ///< uORB pub for satellite info float _rate; ///< position update rate bool _fake_gps; ///< fake gps output @@ -161,7 +164,8 @@ GPS::GPS(const char *uart_path, bool fake_gps) : _mode_changed(false), _mode(GPS_DRIVER_MODE_UBX), _Helper(nullptr), - _report_pub(-1), + _report_gps_pos_pub(-1), + _report_sat_info_pub(-1), _rate(0.0f), _fake_gps(fake_gps) { @@ -172,7 +176,8 @@ GPS::GPS(const char *uart_path, bool fake_gps) : /* we need this potentially before it could be set in task_main */ g_dev = this; - memset(&_report, 0, sizeof(_report)); + memset(&_report_gps_pos, 0, sizeof(_report_gps_pos)); + memset(&_report_sat_info, 0, sizeof(_report_sat_info)); _debug_enabled = true; } @@ -271,33 +276,33 @@ GPS::task_main() if (_fake_gps) { - _report.timestamp_position = hrt_absolute_time(); - _report.lat = (int32_t)47.378301e7f; - _report.lon = (int32_t)8.538777e7f; - _report.alt = (int32_t)1200e3f; - _report.timestamp_variance = hrt_absolute_time(); - _report.s_variance_m_s = 10.0f; - _report.p_variance_m = 10.0f; - _report.c_variance_rad = 0.1f; - _report.fix_type = 3; - _report.eph_m = 0.9f; - _report.epv_m = 1.8f; - _report.timestamp_velocity = hrt_absolute_time(); - _report.vel_n_m_s = 0.0f; - _report.vel_e_m_s = 0.0f; - _report.vel_d_m_s = 0.0f; - _report.vel_m_s = sqrtf(_report.vel_n_m_s * _report.vel_n_m_s + _report.vel_e_m_s * _report.vel_e_m_s + _report.vel_d_m_s * _report.vel_d_m_s); - _report.cog_rad = 0.0f; - _report.vel_ned_valid = true; + _report_gps_pos.timestamp_position = hrt_absolute_time(); + _report_gps_pos.lat = (int32_t)47.378301e7f; + _report_gps_pos.lon = (int32_t)8.538777e7f; + _report_gps_pos.alt = (int32_t)1200e3f; + _report_gps_pos.timestamp_variance = hrt_absolute_time(); + _report_gps_pos.s_variance_m_s = 10.0f; + _report_gps_pos.p_variance_m = 10.0f; + _report_gps_pos.c_variance_rad = 0.1f; + _report_gps_pos.fix_type = 3; + _report_gps_pos.eph_m = 0.9f; + _report_gps_pos.epv_m = 1.8f; + _report_gps_pos.timestamp_velocity = hrt_absolute_time(); + _report_gps_pos.vel_n_m_s = 0.0f; + _report_gps_pos.vel_e_m_s = 0.0f; + _report_gps_pos.vel_d_m_s = 0.0f; + _report_gps_pos.vel_m_s = sqrtf(_report_gps_pos.vel_n_m_s * _report_gps_pos.vel_n_m_s + _report_gps_pos.vel_e_m_s * _report_gps_pos.vel_e_m_s + _report_gps_pos.vel_d_m_s * _report_gps_pos.vel_d_m_s); + _report_gps_pos.cog_rad = 0.0f; + _report_gps_pos.vel_ned_valid = true; //no time and satellite information simulated if (!(_pub_blocked)) { - if (_report_pub > 0) { - orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + if (_report_gps_pos_pub > 0) { + orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos); } else { - _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + _report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos); } } @@ -313,11 +318,11 @@ GPS::task_main() switch (_mode) { case GPS_DRIVER_MODE_UBX: - _Helper = new UBX(_serial_fd, &_report); + _Helper = new UBX(_serial_fd, &_report_gps_pos, &_report_sat_info, UBX_ENABLE_NAV_SVINFO); break; case GPS_DRIVER_MODE_MTK: - _Helper = new MTK(_serial_fd, &_report); + _Helper = new MTK(_serial_fd, &_report_gps_pos); break; default: @@ -332,20 +337,33 @@ GPS::task_main() // GPS is obviously detected successfully, reset statistics _Helper->reset_update_rates(); - while (_Helper->receive(TIMEOUT_5HZ) > 0 && !_task_should_exit) { + int helper_ret; + while ((helper_ret = _Helper->receive(TIMEOUT_5HZ)) > 0 && !_task_should_exit) { // lock(); /* opportunistic publishing - else invalid data would end up on the bus */ if (!(_pub_blocked)) { - if (_report_pub > 0) { - orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + if (helper_ret & 1) { + if (_report_gps_pos_pub > 0) { + orb_publish(ORB_ID(vehicle_gps_position), _report_gps_pos_pub, &_report_gps_pos); - } else { - _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + } else { + _report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos); + } + } + if (helper_ret & 2) { + if (_report_sat_info_pub > 0) { + orb_publish(ORB_ID(satellite_info), _report_sat_info_pub, &_report_sat_info); + + } else { + _report_sat_info_pub = orb_advertise(ORB_ID(satellite_info), &_report_sat_info); + } } } - last_rate_count++; + if (helper_ret & 1) { // consider only pos info updates for rate calculation */ + last_rate_count++; + } /* measure update rate every 5 seconds */ if (hrt_absolute_time() - last_rate_measurement > RATE_MEASUREMENT_PERIOD) { @@ -357,7 +375,7 @@ GPS::task_main() } if (!_healthy) { - char *mode_str = "unknown"; + const char *mode_str = "unknown"; switch (_mode) { case GPS_DRIVER_MODE_UBX: @@ -447,11 +465,11 @@ GPS::print_info() warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK"); - if (_report.timestamp_position != 0) { - warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report.fix_type, - _report.satellites_used, (double)(hrt_absolute_time() - _report.timestamp_position) / 1000.0f); - warnx("lat: %d, lon: %d, alt: %d", _report.lat, _report.lon, _report.alt); - warnx("eph: %.2fm, epv: %.2fm", (double)_report.eph_m, (double)_report.epv_m); + if (_report_gps_pos.timestamp_position != 0) { + warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report_gps_pos.fix_type, + _report_gps_pos.satellites_used, (double)(hrt_absolute_time() - _report_gps_pos.timestamp_position) / 1000.0); + warnx("lat: %d, lon: %d, alt: %d", _report_gps_pos.lat, _report_gps_pos.lon, _report_gps_pos.alt); + warnx("eph: %.2fm, epv: %.2fm", (double)_report_gps_pos.eph_m, (double)_report_gps_pos.epv_m); warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate()); warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate()); warnx("rate publication:\t%6.2f Hz", (double)_rate); @@ -578,7 +596,7 @@ gps_main(int argc, char *argv[]) { /* set to default */ - char *device_name = GPS_DEFAULT_UART_PORT; + const char *device_name = GPS_DEFAULT_UART_PORT; bool fake_gps = false; /* diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index 462875b6c..dd47572b4 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -65,9 +65,13 @@ #define UBX_WAIT_BEFORE_READ 20 // ms, wait before reading to save read() calls #define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval -UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position) : +#define MIN(X,Y) ((X) < (Y) ? (X) : (Y)) + +UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info, const bool &enable_sat_info) : _fd(fd), _gps_position(gps_position), + _satellite_info(satellite_info), + _enable_sat_info(enable_sat_info), _configured(false), _waiting_for_ack(false), _disable_cmd_last(0) @@ -84,14 +88,19 @@ UBX::configure(unsigned &baudrate) { _configured = false; /* try different baudrates */ - const unsigned baudrates_to_try[] = {9600, 38400, 19200, 57600, 115200}; + const unsigned baudrates[] = {9600, 38400, 19200, 57600, 115200}; - int baud_i; + unsigned baud_i; - for (baud_i = 0; baud_i < 5; baud_i++) { - baudrate = baudrates_to_try[baud_i]; + for (baud_i = 0; baud_i < sizeof(baudrates) / sizeof(baudrates[0]); baud_i++) { + baudrate = baudrates[baud_i]; set_baudrate(_fd, baudrate); + /* flush input and wait for at least 20 ms silence */ + decode_init(); + wait_for_ack(20); + decode_init(); + /* Send a CFG-PRT message to set the UBX protocol for in and out * and leave the baudrate as it is, we just want an ACK-ACK from this */ @@ -107,7 +116,7 @@ UBX::configure(unsigned &baudrate) cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; - cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; + cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; cfg_prt_packet.baudRate = baudrate; cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; @@ -125,7 +134,7 @@ UBX::configure(unsigned &baudrate) cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; - cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; + cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; cfg_prt_packet.baudRate = UBX_CFG_PRT_PAYLOAD_BAUDRATE; cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; @@ -144,7 +153,7 @@ UBX::configure(unsigned &baudrate) break; } - if (baud_i >= 5) { + if (baud_i >= sizeof(baudrates) / sizeof(baudrates[0])) { return 1; } @@ -220,14 +229,14 @@ UBX::configure(unsigned &baudrate) return 1; } -#ifdef UBX_ENABLE_NAV_SVINFO - configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5); + if (_enable_sat_info) { + configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5); - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { - warnx("MSG CFG FAIL: NAV SVINFO"); - return 1; + if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { + warnx("MSG CFG FAIL: NAV SVINFO"); + return 1; + } } -#endif configure_message_rate(UBX_CLASS_MON, UBX_MESSAGE_MON_HW, 1); @@ -244,14 +253,13 @@ int UBX::wait_for_ack(unsigned timeout) { _waiting_for_ack = true; - uint64_t time_started = hrt_absolute_time(); + uint64_t time_end = hrt_absolute_time() + timeout * 1000; - while (hrt_absolute_time() < time_started + timeout * 1000) { + while ((timeout = (time_end - hrt_absolute_time()) / 1000) > 0) { if (receive(timeout) > 0) { if (!_waiting_for_ack) { return 1; } - } else { return -1; // timeout or error receiving, or NAK } @@ -275,7 +283,7 @@ UBX::receive(unsigned timeout) ssize_t count = 0; - bool handled = false; + int handled = 0; while (true) { @@ -290,7 +298,7 @@ UBX::receive(unsigned timeout) } else if (ret == 0) { /* return success after short delay after receiving a packet or timeout after long delay */ if (handled) { - return 1; + return handled; } else { return -1; @@ -311,8 +319,7 @@ UBX::receive(unsigned timeout) /* pass received bytes to the packet decoder */ for (int i = 0; i < count; i++) { if (parse_char(buf[i]) > 0) { - if (handle_message() > 0) - handled = true; + handled |= handle_message(); } } } @@ -334,6 +341,7 @@ UBX::parse_char(uint8_t b) case UBX_DECODE_UNINIT: if (b == UBX_SYNC1) { _decode_state = UBX_DECODE_GOT_SYNC1; + //### printf("\nA"); } break; @@ -342,11 +350,13 @@ UBX::parse_char(uint8_t b) case UBX_DECODE_GOT_SYNC1: if (b == UBX_SYNC2) { _decode_state = UBX_DECODE_GOT_SYNC2; + //### printf("B"); } else { /* Second start symbol was wrong, reset state machine */ decode_init(); /* don't return error, it can be just false sync1 */ + //### printf("-"); } break; @@ -357,24 +367,28 @@ UBX::parse_char(uint8_t b) add_byte_to_checksum(b); _message_class = b; _decode_state = UBX_DECODE_GOT_CLASS; + //### printf("C"); break; case UBX_DECODE_GOT_CLASS: add_byte_to_checksum(b); _message_id = b; _decode_state = UBX_DECODE_GOT_MESSAGEID; + //### printf("D"); break; case UBX_DECODE_GOT_MESSAGEID: add_byte_to_checksum(b); _payload_size = b; //this is the first length byte _decode_state = UBX_DECODE_GOT_LENGTH1; + //### printf("E"); break; case UBX_DECODE_GOT_LENGTH1: add_byte_to_checksum(b); _payload_size += b << 8; // here comes the second byte of length _decode_state = UBX_DECODE_GOT_LENGTH2; + //### printf("F"); break; case UBX_DECODE_GOT_LENGTH2: @@ -389,6 +403,7 @@ UBX::parse_char(uint8_t b) if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes /* compare checksum */ if (_rx_ck_a == _rx_buffer[_rx_count - 1] && _rx_ck_b == _rx_buffer[_rx_count]) { + //### printf("O\n"); return 1; // message received successfully } else { @@ -399,6 +414,7 @@ UBX::parse_char(uint8_t b) } else if (_rx_count < RECV_BUFFER_SIZE) { _rx_count++; + //### printf("."); } else { warnx("ubx: buffer full 0x%02x-0x%02x L%u", (unsigned)_message_class, (unsigned)_message_id, _payload_size); @@ -489,65 +505,37 @@ UBX::handle_message() break; } -#ifdef UBX_ENABLE_NAV_SVINFO case UBX_MESSAGE_NAV_SVINFO: { //printf("GOT NAV_SVINFO\n"); + if (!_enable_sat_info) { // if satellite info processing not enabled: + break; // ignore and disable NAV-SVINFO message + } const int length_part1 = 8; gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer; const int length_part2 = 12; gps_bin_nav_svinfo_part2_packet_t *packet_part2; - uint8_t satellites_used = 0; - int i; - //printf("Number of Channels: %d\n", packet_part1->numCh); - for (i = 0; i < packet_part1->numCh; i++) { - /* set pointer to sattelite_i information */ - packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) & (_rx_buffer[length_part1 + i * length_part2]); + for (_satellite_info->count = 0; + _satellite_info->count < MIN(packet_part1->numCh, sizeof(_satellite_info->snr) / sizeof(_satellite_info->snr[0])); + _satellite_info->count++) { + /* set pointer to satellite_i information */ + packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) & (_rx_buffer[length_part1 + _satellite_info->count* length_part2]); /* write satellite information to global storage */ - uint8_t sv_used = packet_part2->flags & 0x01; - - if (sv_used) { - /* count SVs used for NAV */ - satellites_used++; - } - - /* record info for all channels, whether or not the SV is used for NAV */ - _gps_position->satellite_used[i] = sv_used; - _gps_position->satellite_snr[i] = packet_part2->cno; - _gps_position->satellite_elevation[i] = (uint8_t)(packet_part2->elev); - _gps_position->satellite_azimuth[i] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f); - _gps_position->satellite_prn[i] = packet_part2->svid; - //printf("SAT %d: %d %d %d %d\n", i, (int)sv_used, (int)packet_part2->cno, (int)(uint8_t)(packet_part2->elev), (int)packet_part2->svid); - } - - for (i = packet_part1->numCh; i < 20; i++) { - /* unused channels have to be set to zero for e.g. MAVLink */ - _gps_position->satellite_prn[i] = 0; - _gps_position->satellite_used[i] = 0; - _gps_position->satellite_snr[i] = 0; - _gps_position->satellite_elevation[i] = 0; - _gps_position->satellite_azimuth[i] = 0; + _satellite_info->used[_satellite_info->count] = packet_part2->flags & 0x01; + _satellite_info->snr[_satellite_info->count] = packet_part2->cno; + _satellite_info->elevation[_satellite_info->count] = (uint8_t)(packet_part2->elev); + _satellite_info->azimuth[_satellite_info->count] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f); + _satellite_info->svid[_satellite_info->count] = packet_part2->svid; + //printf("SAT %d: %d %d %d %d\n", _satellite_info->count, (int)sv_used, (int)packet_part2->cno, (int)(uint8_t)(packet_part2->elev), (int)packet_part2->svid); } - /* Note: _gps_position->satellites_visible is taken from NAV-SOL now. */ - /* _gps_position->satellites_visible = satellites_used; */ // visible ~= used but we are interested in the used ones - /* TODO: satellites_used may be written into a new field after sat monitoring data got separated from _gps_position */ + _satellite_info->timestamp = hrt_absolute_time(); - if (packet_part1->numCh > 0) { - _gps_position->satellite_info_available = true; - - } else { - _gps_position->satellite_info_available = false; - } - - _gps_position->timestamp_satellites = hrt_absolute_time(); - - ret = 1; + ret = 2; break; } -#endif /* #ifdef UBX_ENABLE_NAV_SVINFO */ case UBX_MESSAGE_NAV_VELNED: { // printf("GOT NAV_VELNED\n"); @@ -650,7 +638,6 @@ UBX::handle_message() warnx("ubx: not acknowledged"); /* configuration obviously not successful */ _waiting_for_ack = false; - ret = -1; break; } diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index b844c315e..90aeffedc 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -48,9 +48,7 @@ #include "gps_helper.h" -/* TODO: processing of NAV_SVINFO disabled, has to be re-written as an optional feature */ -/* TODO: make this a command line option, allocate buffer dynamically */ -#undef UBX_ENABLE_NAV_SVINFO +#define UBX_ENABLE_NAV_SVINFO 1 /* TODO: make this a command line option, allocate buffer(s) dynamically */ #define UBX_SYNC1 0xB5 #define UBX_SYNC2 0x62 @@ -378,7 +376,7 @@ typedef enum { /* calculate parser rx buffer size dependent on NAV_SVINFO enabled or not */ /* TODO: make this a command line option, allocate buffer dynamically */ #define RECV_BUFFER_OVERHEAD 10 // add this to the maximum Rx msg payload size to account for msg overhead */ -#ifdef UBX_ENABLE_NAV_SVINFO +#if (UBX_ENABLE_NAV_SVINFO != 0) #define RECV_BUFFER_SIZE (UBX_NAV_SVINFO_RX_PAYLOAD_SIZE + RECV_BUFFER_OVERHEAD) #else #define RECV_BUFFER_SIZE (UBX_MAX_RX_PAYLOAD_SIZE + RECV_BUFFER_OVERHEAD) @@ -387,7 +385,7 @@ typedef enum { class UBX : public GPS_Helper { public: - UBX(const int &fd, struct vehicle_gps_position_s *gps_position); + UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info, const bool &enable_sat_info); ~UBX(); int receive(unsigned timeout); int configure(unsigned &baudrate); @@ -434,6 +432,8 @@ private: int _fd; struct vehicle_gps_position_s *_gps_position; + struct satellite_info_s *_satellite_info; + bool _enable_sat_info; bool _configured; bool _waiting_for_ack; uint8_t _message_class_needed; diff --git a/src/modules/uORB/topics/satellite_info.h b/src/modules/uORB/topics/satellite_info.h index 5f799eda4..37c2faa96 100644 --- a/src/modules/uORB/topics/satellite_info.h +++ b/src/modules/uORB/topics/satellite_info.h @@ -53,14 +53,17 @@ /** * GNSS Satellite Info. */ + +#define SAT_INFO_MAX_SATELLITES 20 + struct satellite_info_s { - uint64_t timestamp; /**< Timestamp of satellite information */ - uint8_t count; /**< Number of satellites in satellite_...[] arrays */ - uint8_t svid[20]; /**< Space vehicle ID [1..255], see scheme below */ - uint8_t used[20]; /**< 0: Satellite not used, 1: used for navigation */ - uint8_t elevation[20]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ - uint8_t azimuth[20]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */ - uint8_t snr[20]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */ + uint64_t timestamp; /**< Timestamp of satellite info */ + uint8_t count; /**< Number of satellites in satellite info */ + uint8_t svid[SAT_INFO_MAX_SATELLITES]; /**< Space vehicle ID [1..255], see scheme below */ + uint8_t used[SAT_INFO_MAX_SATELLITES]; /**< 0: Satellite not used, 1: used for navigation */ + uint8_t elevation[SAT_INFO_MAX_SATELLITES]; /**< Elevation (0: right on top of receiver, 90: on the horizon) of satellite */ + uint8_t azimuth[SAT_INFO_MAX_SATELLITES]; /**< Direction of satellite, 0: 0 deg, 255: 360 deg. */ + uint8_t snr[SAT_INFO_MAX_SATELLITES]; /**< dBHz, Signal to noise ratio of satellite C/N0, range 0..99, zero when not tracking this satellite. */ }; /** -- cgit v1.2.3 From 018eeeecad748959a8afa4845a536e897a57249d Mon Sep 17 00:00:00 2001 From: Kynos Date: Sun, 8 Jun 2014 15:56:42 +0200 Subject: Merged ubx driver part of pull request #1031 --- src/drivers/gps/ubx.cpp | 15 +++++++++++---- src/drivers/gps/ubx.h | 2 ++ 2 files changed, 13 insertions(+), 4 deletions(-) diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index dd47572b4..0708e23b4 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -74,6 +74,8 @@ UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct sate _enable_sat_info(enable_sat_info), _configured(false), _waiting_for_ack(false), + _got_posllh(false), + _got_velned(false), _disable_cmd_last(0) { decode_init(); @@ -208,7 +210,7 @@ UBX::configure(unsigned &baudrate) return 1; } - configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 1); + configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 5); if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { warnx("MSG CFG FAIL: NAV TIMEUTC"); @@ -286,9 +288,10 @@ UBX::receive(unsigned timeout) int handled = 0; while (true) { + bool ready_to_return = _configured ? (_got_posllh && _got_velned) : handled; /* poll for new data, wait for only UBX_PACKET_TIMEOUT (2ms) if something already received */ - int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), handled ? UBX_PACKET_TIMEOUT : timeout); + int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), ready_to_return ? UBX_PACKET_TIMEOUT : timeout); if (ret < 0) { /* something went wrong when polling */ @@ -297,7 +300,9 @@ UBX::receive(unsigned timeout) } else if (ret == 0) { /* return success after short delay after receiving a packet or timeout after long delay */ - if (handled) { + if (ready_to_return) { + _got_posllh = false; + _got_velned = false; return handled; } else { @@ -456,7 +461,8 @@ UBX::handle_message() _rate_count_lat_lon++; - ret = 1; + _got_posllh = true; + ret = 1; break; } @@ -552,6 +558,7 @@ UBX::handle_message() _rate_count_vel++; + _got_velned = true; ret = 1; break; } diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index 90aeffedc..50df3ada2 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -436,6 +436,8 @@ private: bool _enable_sat_info; bool _configured; bool _waiting_for_ack; + bool _got_posllh; + bool _got_velned; uint8_t _message_class_needed; uint8_t _message_id_needed; ubx_decode_state_t _decode_state; -- cgit v1.2.3 From 3538773b99d4231bf8a64e9c257cfe0299a93021 Mon Sep 17 00:00:00 2001 From: Kynos Date: Sun, 8 Jun 2014 16:05:04 +0200 Subject: Initialize rate values Initialize rate values (else invalid rates wil be displayed during the first measurement interval). --- src/drivers/gps/gps_helper.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/gps/gps_helper.h b/src/drivers/gps/gps_helper.h index d14a95afe..3623397b2 100644 --- a/src/drivers/gps/gps_helper.h +++ b/src/drivers/gps/gps_helper.h @@ -62,8 +62,8 @@ protected: uint8_t _rate_count_lat_lon; uint8_t _rate_count_vel; - float _rate_lat_lon; - float _rate_vel; + float _rate_lat_lon = 0.0f; + float _rate_vel = 0.0f; uint64_t _interval_rate_start; }; -- cgit v1.2.3 From 07458b284d4cea48bc3b6e0cb5dcaba1c2c1d4d6 Mon Sep 17 00:00:00 2001 From: Kynos Date: Sun, 8 Jun 2014 17:54:50 +0200 Subject: Gps driver: make enable_sat_info a command line option --- src/drivers/gps/gps.cpp | 28 +++++++++++++++++++--------- 1 file changed, 19 insertions(+), 9 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index d8e2bd797..f4d2f4b44 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -83,7 +83,7 @@ static const int ERROR = -1; class GPS : public device::CDev { public: - GPS(const char *uart_path, bool fake_gps); + GPS(const char *uart_path, bool fake_gps, bool enable_sat_info); virtual ~GPS(); virtual int init(); @@ -113,6 +113,7 @@ private: orb_advert_t _report_sat_info_pub; ///< uORB pub for satellite info float _rate; ///< position update rate bool _fake_gps; ///< fake gps output + bool _enable_sat_info; ///< enable sat info /** @@ -157,7 +158,7 @@ GPS *g_dev; } -GPS::GPS(const char *uart_path, bool fake_gps) : +GPS::GPS(const char *uart_path, bool fake_gps, bool enable_sat_info) : CDev("gps", GPS_DEVICE_PATH), _task_should_exit(false), _healthy(false), @@ -167,7 +168,8 @@ GPS::GPS(const char *uart_path, bool fake_gps) : _report_gps_pos_pub(-1), _report_sat_info_pub(-1), _rate(0.0f), - _fake_gps(fake_gps) + _fake_gps(fake_gps), + _enable_sat_info(enable_sat_info) { /* store port name */ strncpy(_port, uart_path, sizeof(_port)); @@ -318,7 +320,7 @@ GPS::task_main() switch (_mode) { case GPS_DRIVER_MODE_UBX: - _Helper = new UBX(_serial_fd, &_report_gps_pos, &_report_sat_info, UBX_ENABLE_NAV_SVINFO); + _Helper = new UBX(_serial_fd, &_report_gps_pos, &_report_sat_info, _enable_sat_info); break; case GPS_DRIVER_MODE_MTK: @@ -464,6 +466,7 @@ GPS::print_info() } warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK"); + warnx("sat info: %s", (_enable_sat_info) ? "enabled" : "disabled"); if (_report_gps_pos.timestamp_position != 0) { warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report_gps_pos.fix_type, @@ -487,7 +490,7 @@ namespace gps GPS *g_dev; -void start(const char *uart_path, bool fake_gps); +void start(const char *uart_path, bool fake_gps, bool enable_sat_info); void stop(); void test(); void reset(); @@ -497,7 +500,7 @@ void info(); * Start the driver. */ void -start(const char *uart_path, bool fake_gps) +start(const char *uart_path, bool fake_gps, bool enable_sat_info) { int fd; @@ -505,7 +508,7 @@ start(const char *uart_path, bool fake_gps) errx(1, "already started"); /* create the driver */ - g_dev = new GPS(uart_path, fake_gps); + g_dev = new GPS(uart_path, fake_gps, enable_sat_info); if (g_dev == nullptr) goto fail; @@ -598,6 +601,7 @@ gps_main(int argc, char *argv[]) /* set to default */ const char *device_name = GPS_DEFAULT_UART_PORT; bool fake_gps = false; + bool enable_sat_info = false; /* * Start/load the driver. @@ -619,7 +623,13 @@ gps_main(int argc, char *argv[]) fake_gps = true; } - gps::start(device_name, fake_gps); + /* Detect sat info option */ + for (int i = 2; i < argc; i++) { + if (!strcmp(argv[i], "-s")) + enable_sat_info = true; + } + + gps::start(device_name, fake_gps, enable_sat_info); } if (!strcmp(argv[1], "stop")) @@ -644,5 +654,5 @@ gps_main(int argc, char *argv[]) gps::info(); out: - errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n][-f]"); + errx(1, "unrecognized command, try 'start', 'stop', 'test', 'reset' or 'status' [-d /dev/ttyS0-n][-f][-s]"); } -- cgit v1.2.3 From a6cf04a6ff623b7d39a97c70f837198b6c064f5b Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sun, 8 Jun 2014 14:08:22 -0400 Subject: Create system state entry in dataman - ATTN Anton Create persistent system state id for data manager to store system state that will persist across resets. --- ROMFS/px4fmu_common/init.d/rcS | 10 +++--- src/modules/dataman/dataman.c | 50 ++++++++++++++++++++++++++--- src/modules/dataman/dataman.h | 26 ++++++++++++++- src/modules/mavlink/mavlink_main.cpp | 54 ++++++++++++++++++++++++++++++-- src/modules/navigator/navigator_main.cpp | 9 ++++++ 5 files changed, 136 insertions(+), 13 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 6d06f897a..13c08f405 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -402,6 +402,11 @@ then fi fi + # + # Start the datamanager + # + dataman start + # # MAVLink # @@ -544,11 +549,6 @@ then fi fi - # - # Start the datamanager - # - dataman start - # # Start the navigator # diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c index 1a65313e8..96dc98f2a 100644 --- a/src/modules/dataman/dataman.c +++ b/src/modules/dataman/dataman.c @@ -61,6 +61,8 @@ __EXPORT int dataman_main(int argc, char *argv[]); __EXPORT ssize_t dm_read(dm_item_t item, unsigned char index, void *buffer, size_t buflen); __EXPORT ssize_t dm_write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const void *buffer, size_t buflen); __EXPORT int dm_clear(dm_item_t item); +__EXPORT void dm_lock(dm_item_t item); +__EXPORT void dm_unlock(dm_item_t item); __EXPORT int dm_restart(dm_reset_reason restart_type); /** Types of function calls supported by the worker task */ @@ -113,12 +115,17 @@ static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS] = { DM_KEY_FENCE_POINTS_MAX, DM_KEY_WAYPOINTS_OFFBOARD_0_MAX, DM_KEY_WAYPOINTS_OFFBOARD_1_MAX, - DM_KEY_WAYPOINTS_ONBOARD_MAX + DM_KEY_WAYPOINTS_ONBOARD_MAX, + DM_KEY_SYSTEM_STATE_MAX }; /* Table of offset for index 0 of each item type */ static unsigned int g_key_offsets[DM_KEY_NUM_KEYS]; +/* Item type lock mutexes */ +static sem_t *g_item_locks[DM_KEY_NUM_KEYS]; +static sem_t g_sys_state_mutex; + /* The data manager store file handle and file name */ static int g_fd = -1, g_task_fd = -1; static const char *k_data_manager_device_path = "/fs/microsd/dataman"; @@ -138,22 +145,22 @@ static work_q_t g_work_q; /* pending work items. To be consumed by worker thread sem_t g_work_queued_sema; /* To notify worker thread a work item has been queued */ sem_t g_init_sema; -static bool g_task_should_exit; /**< if true, dataman task should exit */ +static bool g_task_should_exit; /**< if true, dataman task should exit */ #define DM_SECTOR_HDR_SIZE 4 /* data manager per item header overhead */ static const unsigned k_sector_size = DM_MAX_DATA_SIZE + DM_SECTOR_HDR_SIZE; /* total item sorage space */ static void init_q(work_q_t *q) { - sq_init(&(q->q)); /* Initialize the NuttX queue structure */ + sq_init(&(q->q)); /* Initialize the NuttX queue structure */ sem_init(&(q->mutex), 1, 1); /* Queue is initially unlocked */ - q->size = q->max_size = 0; /* Queue is initially empty */ + q->size = q->max_size = 0; /* Queue is initially empty */ } static inline void destroy_q(work_q_t *q) { - sem_destroy(&(q->mutex)); /* Destroy the queue lock */ + sem_destroy(&(q->mutex)); /* Destroy the queue lock */ } static inline void @@ -567,6 +574,32 @@ dm_clear(dm_item_t item) return enqueue_work_item_and_wait_for_result(work); } +__EXPORT void +dm_lock(dm_item_t item) +{ + /* Make sure data manager has been started and is not shutting down */ + if ((g_fd < 0) || g_task_should_exit) + return; + if (item >= DM_KEY_NUM_KEYS) + return; + if (g_item_locks[item]) { + sem_wait(g_item_locks[item]); + } +} + +__EXPORT void +dm_unlock(dm_item_t item) +{ + /* Make sure data manager has been started and is not shutting down */ + if ((g_fd < 0) || g_task_should_exit) + return; + if (item >= DM_KEY_NUM_KEYS) + return; + if (g_item_locks[item]) { + sem_post(g_item_locks[item]); + } +} + /* Tell the data manager about the type of the last reset */ __EXPORT int dm_restart(dm_reset_reason reason) @@ -607,6 +640,12 @@ task_main(int argc, char *argv[]) for (unsigned i = 0; i < dm_number_of_funcs; i++) g_func_counts[i] = 0; + /* Initialize the item type locks, for now only DM_KEY_SYSTEM_STATE supports locking */ + sem_init(&g_sys_state_mutex, 1, 1); /* Initially unlocked */ + for (unsigned i = 0; i < DM_KEY_NUM_KEYS; i++) + g_item_locks[i] = NULL; + g_item_locks[DM_KEY_SYSTEM_STATE] = &g_sys_state_mutex; + g_task_should_exit = false; init_q(&g_work_q); @@ -742,6 +781,7 @@ task_main(int argc, char *argv[]) destroy_q(&g_work_q); destroy_q(&g_free_q); sem_destroy(&g_work_queued_sema); + sem_destroy(&g_sys_state_mutex); return 0; } diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h index 1dfb26f73..f2b6cd4d3 100644 --- a/src/modules/dataman/dataman.h +++ b/src/modules/dataman/dataman.h @@ -53,6 +53,7 @@ extern "C" { DM_KEY_WAYPOINTS_OFFBOARD_0, /* Mission way point coordinates sent over mavlink */ DM_KEY_WAYPOINTS_OFFBOARD_1, /* (alernate between 0 and 1) */ DM_KEY_WAYPOINTS_ONBOARD, /* Mission way point coordinates generated onboard */ + DM_KEY_SYSTEM_STATE, /* Persistent system state storage */ DM_KEY_NUM_KEYS /* Total number of item types defined */ } dm_item_t; @@ -62,7 +63,8 @@ extern "C" { DM_KEY_FENCE_POINTS_MAX = GEOFENCE_MAX_VERTICES, DM_KEY_WAYPOINTS_OFFBOARD_0_MAX = NUM_MISSIONS_SUPPORTED, DM_KEY_WAYPOINTS_OFFBOARD_1_MAX = NUM_MISSIONS_SUPPORTED, - DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED + DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED, + DM_KEY_SYSTEM_STATE_MAX = 1 }; /** Data persistence levels */ @@ -101,6 +103,18 @@ extern "C" { size_t buflen /* Length in bytes of data to retrieve */ ); + /** Lock all items of this type */ + __EXPORT void + dm_lock( + dm_item_t item /* The item type to clear */ + ); + + /** Unlock all items of this type */ + __EXPORT void + dm_unlock( + dm_item_t item /* The item type to clear */ + ); + /** Erase all items of this type */ __EXPORT int dm_clear( @@ -113,6 +127,16 @@ extern "C" { dm_reset_reason restart_type /* The last reset type */ ); + /* NOTE: The following structure defines the persistent system state data stored in the single + entry DM_KEY_SYSTEM_STATE_KEY item type. It contains global system state information that + needs to survive restarts. This definition is application specific so it doesn't really belong + in this header, but till I find it a better home here it is */ + + typedef struct { + char current_offboard_waypoint_id; /* the index of the active offboard waypoint data */ + /* (DM_KEY_WAYPOINTS_OFFBOARD_n) or -1 for none */ + } persistent_system_state_t; + #ifdef __cplusplus } #endif diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index e300be074..cb1b762a7 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -952,6 +952,8 @@ int Mavlink::map_mission_item_to_mavlink_mission_item(const struct mission_item_ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) { + persistent_system_state_t sys_state; + state->size = 0; state->max_size = MAVLINK_WPM_MAX_WP_COUNT; state->current_state = MAVLINK_WPM_STATE_IDLE; @@ -962,6 +964,10 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) state->timestamp_last_send_request = 0; state->timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; state->current_dataman_id = 0; + if (dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state)) == sizeof(sys_state)) { + if ((sys_state.current_offboard_waypoint_id >= 0) && (sys_state.current_offboard_waypoint_id <= 1)) + state->current_dataman_id = sys_state.current_offboard_waypoint_id; + } } /* @@ -1428,12 +1434,38 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) mission.dataman_id = 0; } - if (dm_write(dm_next, wp.seq, DM_PERSIST_IN_FLIGHT_RESET, &mission_item, len) != len) { + if (dm_write(dm_next, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, len) != len) { mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD"); _wpm->current_state = MAVLINK_WPM_STATE_IDLE; break; } + // offboard mission data saved correctly, now update the persistent system state + { + persistent_system_state_t state; + bool dm_result; + // Since we are doing a read-modify-write we must lock the item type + dm_lock(DM_KEY_SYSTEM_STATE); + // first read in the current state data. There may eventually be data other than the offboard index + // and we must preserve it + if (dm_read(DM_KEY_SYSTEM_STATE, 0, &state, sizeof(state)) != sizeof(state)) { + // Not sure how to handle this? It means that either the item was never + // written, or fields have been added to the system state struct. In any case + // fields that may not be ours need to be initialized to sane values. + // For now the offboard index is the only field, so for now there + // is nothing to do here. + } + state.current_offboard_waypoint_id = mission.dataman_id; + dm_result = dm_write(DM_KEY_SYSTEM_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) != sizeof(state); + dm_unlock(DM_KEY_SYSTEM_STATE); + if (dm_result) { + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); + mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD"); + _wpm->current_state = MAVLINK_WPM_STATE_IDLE; + break; + } + } + // if (wp.current) { // warnx("current is: %d", wp.seq); @@ -1485,7 +1517,25 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) publish_mission(); if (dm_clear(DM_KEY_WAYPOINTS_OFFBOARD_0) == OK && dm_clear(DM_KEY_WAYPOINTS_OFFBOARD_1) == OK) { - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); + persistent_system_state_t state; + bool dm_result; + dm_lock(DM_KEY_SYSTEM_STATE); + // first read in the current state data. There may eventually be data other than the offboard index + // and we must preserve it + if (dm_read(DM_KEY_SYSTEM_STATE, 0, &state, sizeof(state)) != sizeof(state)) { + // Not sure how to handle this? It means that either the item was never + // written, or fields have been added to the system state struct. In any case + // fields that may not be ours need to be initialized to sane values. + // For now the offboard index is the only field, so we can deal with it here. + } + state.current_offboard_waypoint_id = -1; + dm_result = dm_write(DM_KEY_SYSTEM_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) == sizeof(state); + dm_unlock(DM_KEY_SYSTEM_STATE); + if (dm_result) { + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); + } else { + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); + } } else { mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 06e0c5904..04ea7da0e 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -603,6 +603,15 @@ Navigator::task_main() warnx("Could not clear geofence"); } +#if 0 // *** UNTESTED... Anton, this is for you + /* Get the last offboard mission id */ + persistent_system_state_t sys_state; + if (dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state)) == sizeof(sys_state)) { + if ((sys_state.current_offboard_waypoint_id >= 0) && (sys_state.current_offboard_waypoint_id <= 1)) + _mission.set_offboard_dataman_id(sys_state.current_offboard_waypoint_id); + } +#endif + /* * do subscriptions */ -- cgit v1.2.3 From 0a86fd0d9f3f3ba1a007ff54e1d498e7735d4aa5 Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Sun, 8 Jun 2014 15:21:02 -0400 Subject: Changed struct name used for local_pos_sp --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 21 +++++++++------------ 1 file changed, 9 insertions(+), 12 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 4ee78516f..6a105762b 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -118,7 +118,7 @@ private: int _arming_sub; /**< arming status of outputs */ int _local_pos_sub; /**< vehicle local position */ int _pos_sp_triplet_sub; /**< position setpoint triplet */ - int _offboard_control_pos_sp_sub; /**< offboard control position setpoint */ + int _local_pos_sp_sub; /**< offboard local position setpoint */ orb_advert_t _att_sp_pub; /**< attitude setpoint publication */ orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */ @@ -133,7 +133,6 @@ private: struct position_setpoint_triplet_s _pos_sp_triplet; /**< vehicle global position setpoint triplet */ struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position setpoint */ struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */ - struct vehicle_local_position_setpoint_s _offboard_control_pos_sp; /**< offboard control position setpoint */ struct { @@ -280,7 +279,6 @@ MulticopterPositionControl::MulticopterPositionControl() : memset(&_pos_sp_triplet, 0, sizeof(_pos_sp_triplet)); memset(&_local_pos_sp, 0, sizeof(_local_pos_sp)); memset(&_global_vel_sp, 0, sizeof(_global_vel_sp)); - memset(&_offboard_control_pos_sp, 0, sizeof(_offboard_control_pos_sp)); memset(&_ref_pos, 0, sizeof(_ref_pos)); @@ -532,7 +530,7 @@ MulticopterPositionControl::task_main() _arming_sub = orb_subscribe(ORB_ID(actuator_armed)); _local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); _pos_sp_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet)); - _offboard_control_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); + _local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); parameters_update(true); @@ -671,26 +669,25 @@ MulticopterPositionControl::task_main() } else if (_control_mode.flag_control_offboard_enabled) { /* Offboard control */ - /* Team elikos doesn't really know what it is doing */ bool updated; - orb_check(_offboard_control_pos_sp_sub, &updated); + orb_check(_local_pos_sp_sub, &updated); if (updated) { - orb_copy(ORB_ID(vehicle_local_position_setpoint), _offboard_control_pos_sp_sub, - &_offboard_control_pos_sp); + orb_copy(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_sub, + &_local_pos_sp); } /* Make sure position control is selected i.e. not only velocity control */ if (_control_mode.flag_control_position_enabled) { - _pos_sp(0) = _offboard_control_pos_sp.x; - _pos_sp(1) = _offboard_control_pos_sp.y; + _pos_sp(0) = _local_pos_sp.x; + _pos_sp(1) = _local_pos_sp.y; } if (_control_mode.flag_control_altitude_enabled) { - _pos_sp(2) = _offboard_control_pos_sp.z; + _pos_sp(2) = _local_pos_sp.z; } - _att_sp.yaw_body = _offboard_control_pos_sp.yaw; + _att_sp.yaw_body = _local_pos_sp.yaw; } else { /* AUTO */ -- cgit v1.2.3 From 4ad435b483510158ea8a5b303cd680f9e982df84 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 9 Jun 2014 16:09:03 +0200 Subject: dataman: allow writing empty items with nullptr pointer to data --- src/modules/dataman/dataman.c | 4 +++- src/modules/dataman/dataman.h | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c index 96dc98f2a..14fee7c9a 100644 --- a/src/modules/dataman/dataman.c +++ b/src/modules/dataman/dataman.c @@ -324,7 +324,9 @@ _write(dm_item_t item, unsigned char index, dm_persitence_t persistence, const v buffer[1] = persistence; buffer[2] = 0; buffer[3] = 0; - memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count); + if (count > 0) { + memcpy(buffer + DM_SECTOR_HDR_SIZE, buf, count); + } count += DM_SECTOR_HDR_SIZE; len = -1; diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h index f2b6cd4d3..b25a2a5ef 100644 --- a/src/modules/dataman/dataman.h +++ b/src/modules/dataman/dataman.h @@ -133,7 +133,7 @@ extern "C" { in this header, but till I find it a better home here it is */ typedef struct { - char current_offboard_waypoint_id; /* the index of the active offboard waypoint data */ + char offboard_waypoint_id; /* the index of the active offboard waypoint data */ /* (DM_KEY_WAYPOINTS_OFFBOARD_n) or -1 for none */ } persistent_system_state_t; -- cgit v1.2.3 From cad0877f67c393b698b8fc4f242944c9e1ba1bc5 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 9 Jun 2014 16:10:24 +0200 Subject: mavlink: waypoint manager fixes, mission saving on reboot --- src/modules/mavlink/mavlink_main.cpp | 432 +++++++++++++++---------------- src/modules/mavlink/mavlink_main.h | 13 +- src/modules/navigator/navigator_main.cpp | 6 +- src/modules/uORB/topics/mission.h | 4 +- 4 files changed, 227 insertions(+), 228 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index cb1b762a7..4e0597e80 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -954,20 +954,53 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) { persistent_system_state_t sys_state; + /* init WPM state */ state->size = 0; state->max_size = MAVLINK_WPM_MAX_WP_COUNT; + state->dataman_id = 0; state->current_state = MAVLINK_WPM_STATE_IDLE; state->current_partner_sysid = 0; state->current_partner_compid = 0; + state->current_dataman_id = 0; state->timestamp_lastaction = 0; state->timestamp_last_send_setpoint = 0; state->timestamp_last_send_request = 0; state->timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; - state->current_dataman_id = 0; - if (dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state)) == sizeof(sys_state)) { - if ((sys_state.current_offboard_waypoint_id >= 0) && (sys_state.current_offboard_waypoint_id <= 1)) - state->current_dataman_id = sys_state.current_offboard_waypoint_id; + + int sys_state_size = dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state)); + if (sys_state_size == sizeof(sys_state)) { + if ((sys_state.offboard_waypoint_id >= 0) && (sys_state.offboard_waypoint_id <= 1)) { + state->dataman_id = sys_state.offboard_waypoint_id; + + if (_verbose) { warnx("WPM init: using dataman ID %d", state->dataman_id); } + + /* count waypoints in current waypoints storage */ + dm_item_t dm_id = _wpm->dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; + struct mission_item_s mission_item; + + int seq = 0; + while (seq < state->max_size && dm_read(dm_id, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { + seq++; + } + + if (_verbose) { warnx("WPM init: found %d items", seq); } + + state->size = seq; + + } else { + if (_verbose) { warnx("WPM init: invalid dataman ID %d stored in SYSTEM_STATE", sys_state.offboard_waypoint_id); } + } + + } else { + if (_verbose) { warnx("WPM init: dataman SYSTEM_STATE item has wrong size (%i, should be %u), ignoring", sys_state_size, sizeof(sys_state)); } } + + /* init mission topic */ + mission.count = state->size; + mission.dataman_id = state->dataman_id; + mission.current_index = -1; // TODO store current index in dataman? + + publish_mission(); } /* @@ -985,7 +1018,7 @@ void Mavlink::mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8 mavlink_msg_mission_ack_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpa); mavlink_missionlib_send_message(&msg); - if (_verbose) { warnx("Sent waypoint ack (%u) to ID %u", wpa.type, wpa.target_system); } + if (_verbose) { warnx("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system); } } /* @@ -1009,13 +1042,12 @@ void Mavlink::mavlink_wpm_send_waypoint_current(uint16_t seq) mavlink_missionlib_send_message(&msg); } else if (seq == 0 && _wpm->size == 0) { - /* don't broadcast if no WPs */ } else { - mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds"); + if (_verbose) { warnx("WPM: Send WAYPOINT_CURRENT ERROR: seq %u out of bounds", seq); } - if (_verbose) { warnx("ERROR: index out of bounds"); } + mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds"); } } @@ -1031,25 +1063,15 @@ void Mavlink::mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uin mavlink_msg_mission_count_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpc); mavlink_missionlib_send_message(&msg); - if (_verbose) { warnx("Sent waypoint count (%u) to ID %u", wpc.count, wpc.target_system); } + if (_verbose) { warnx("WPM: Send WAYPOINT_COUNT %u to ID %u", wpc.count, wpc.target_system); } } void Mavlink::mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq) { - + dm_item_t dm_id = _wpm->dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; struct mission_item_s mission_item; - ssize_t len = sizeof(struct mission_item_s); - dm_item_t dm_current; - - if (_wpm->current_dataman_id == 0) { - dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0; - - } else { - dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1; - } - - if (dm_read(dm_current, seq, &mission_item, len) == len) { + if (dm_read(dm_id, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { /* create mission_item_s from mavlink_mission_item_t */ mavlink_mission_item_t wp; @@ -1062,13 +1084,13 @@ void Mavlink::mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t mavlink_msg_mission_item_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wp); mavlink_missionlib_send_message(&msg); - if (_verbose) { warnx("Sent waypoint %u to ID %u", wp.seq, wp.target_system); } + if (_verbose) { warnx("WPM: Send WAYPOINT seq %u to ID %u", wp.seq, wp.target_system); } } else { mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); mavlink_missionlib_send_gcs_string("#audio: Unable to read from micro SD"); - if (_verbose) { warnx("ERROR: could not read WP%u", seq); } + if (_verbose) { warnx("WPM: Send WAYPOINT ERROR: could not read seq %u from dataman ID %i", seq, dm_id); } } } @@ -1084,12 +1106,12 @@ void Mavlink::mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, u mavlink_missionlib_send_message(&msg); _wpm->timestamp_last_send_request = hrt_absolute_time(); - if (_verbose) { warnx("Sent waypoint request %u to ID %u", wpr.seq, wpr.target_system); } + if (_verbose) { warnx("WPM: Send WAYPOINT_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system); } } else { mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity"); - if (_verbose) { warnx("ERROR: Waypoint index exceeds list capacity"); } + if (_verbose) { warnx("WPM: Send WAYPINT_REQUEST ERROR: seq %u exceeds list capacity", seq); } } } @@ -1110,7 +1132,7 @@ void Mavlink::mavlink_wpm_send_waypoint_reached(uint16_t seq) mavlink_msg_mission_item_reached_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wp_reached); mavlink_missionlib_send_message(&msg); - if (_verbose) { warnx("Sent waypoint %u reached message", wp_reached.seq); } + if (_verbose) { warnx("WPM: Send WAYPOINT_REACHED seq %u", wp_reached.seq); } } void Mavlink::mavlink_waypoint_eventloop(uint64_t now) @@ -1120,7 +1142,7 @@ void Mavlink::mavlink_waypoint_eventloop(uint64_t now) mavlink_missionlib_send_gcs_string("Operation timeout"); - if (_verbose) { warnx("Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _wpm->current_state); } + if (_verbose) { warnx("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _wpm->current_state); } _wpm->current_state = MAVLINK_WPM_STATE_IDLE; _wpm->current_partner_sysid = 0; @@ -1143,23 +1165,25 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) mavlink_mission_ack_t wpa; mavlink_msg_mission_ack_decode(msg, &wpa); - if ((msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid) && (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/)) { - _wpm->timestamp_lastaction = now; + if (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/) { + if ((msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid)) { + _wpm->timestamp_lastaction = now; - if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST || _wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) { - if (_wpm->current_wp_id == _wpm->size - 1) { + if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST || _wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) { + if (_wpm->current_wp_id == _wpm->size - 1) { + if (_verbose) { warnx("WPM: MISSION_ACK all items sent, switch to MAVLINK_WPM_STATE_IDLE"); } - _wpm->current_state = MAVLINK_WPM_STATE_IDLE; - _wpm->current_wp_id = 0; + _wpm->current_state = MAVLINK_WPM_STATE_IDLE; + _wpm->current_wp_id = 0; + } } - } - } else { - mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch"); + } else { + mavlink_missionlib_send_gcs_string("REJ. WP CMD: partner id mismatch"); - if (_verbose) { warnx("REJ. WP CMD: curr partner id mismatch"); } + if (_verbose) { warnx("WPM: MISSION_ACK ERROR: rejected, partner ID mismatch"); } + } } - break; } @@ -1172,6 +1196,7 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE) { if (wpc.seq < _wpm->size) { + if (_verbose) { warnx("WPM: MISSION_SET_CURRENT OK (%d)", wpc.seq); } mission.current_index = wpc.seq; publish_mission(); @@ -1180,16 +1205,15 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) // mavlink_wpm_send_waypoint_current(wpc.seq); } else { - mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list"); + if (_verbose) { warnx("WPM: MISSION_SET_CURRENT ERROR: not in list (%d)", wpc.seq); } - if (_verbose) { warnx("IGN WP CURR CMD: Not in list"); } + mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list"); } } else { - mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy"); - - if (_verbose) { warnx("IGN WP CURR CMD: Busy"); } + if (_verbose) { warnx("WPM: MISSION_SET_CURRENT ERROR: busy"); } + mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy"); } } @@ -1205,23 +1229,22 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE || _wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) { if (_wpm->size > 0) { - _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) { warnx("No waypoints send"); } + if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST nothing to send, mission is empty"); } } _wpm->current_count = _wpm->size; mavlink_wpm_send_waypoint_count(msg->sysid, msg->compid, _wpm->current_count); } else { - mavlink_missionlib_send_gcs_string("IGN REQUEST LIST: Busy"); + if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST ERROR: busy"); } - if (_verbose) { warnx("IGN REQUEST LIST: Busy"); } + mavlink_missionlib_send_gcs_string("IGN REQUEST LIST: Busy"); } } @@ -1232,88 +1255,73 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) mavlink_mission_request_t wpr; mavlink_msg_mission_request_decode(msg, &wpr); - if (msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid && wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) { - _wpm->timestamp_lastaction = now; - - if (wpr.seq >= _wpm->size) { - - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list"); - - if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was out of bounds.", wpr.seq); } - - break; - } + if (wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) { + if (msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid) { + _wpm->timestamp_lastaction = now; - /* - * 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) - */ - if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) { + if (wpr.seq >= _wpm->size) { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: ignored, requested seq %u was out of bounds [0 %d]", wpr.seq, _wpm->size - 1); } - if (wpr.seq == 0) { - if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list"); + break; + } - _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS; + /* + * 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) + */ + if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) { + if (wpr.seq == 0) { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u from ID %u, changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } - } else { - mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0"); + _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS; - if (_verbose) { warnx("REJ. WP CMD: First id != 0"); } - - break; - } + } else { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: first id != 0 (%d)", wpr.seq); } - } else if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) { + mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0"); + break; + } - if (wpr.seq == _wpm->current_wp_id) { + } else if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) { + if (wpr.seq == _wpm->current_wp_id) { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u (again) from ID %u, staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } - if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u (again) from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } + } else if (wpr.seq == _wpm->current_wp_id + 1) { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u from ID %u, staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } - } else if (wpr.seq == _wpm->current_wp_id + 1) { + } else { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u from ID %u unexpected, should be %i or %i", wpr.seq, msg->sysid, _wpm->current_wp_id, _wpm->current_wp_id + 1); } - if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_REQUEST of waypoint %u from %u staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected"); + break; + } } else { - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected"); - - if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because the requested waypoint ID (%u) was not the expected (%u or %u).", wpr.seq, _wpm->current_wp_id, _wpm->current_wp_id + 1); } + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: busy (state %d).", _wpm->current_state); } + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); break; } - } else { - - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); - - if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST because i'm doing something else already (state=%i).", _wpm->current_state); } + _wpm->current_wp_id = wpr.seq; + _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS; - break; - } + if (wpr.seq < _wpm->size) { + mavlink_wpm_send_waypoint(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); - _wpm->current_wp_id = wpr.seq; - _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS; - - if (wpr.seq < _wpm->size) { + } else { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u out of bounds", wpr.seq); } - mavlink_wpm_send_waypoint(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); + } } else { - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); - - if (_verbose) { warnx("ERROR: Waypoint %u out of bounds", wpr.seq); } - } - - - } else { - //we we're target but already communicating with someone else - if ((wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) && !(msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid)) { - - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); + mavlink_missionlib_send_gcs_string("REJ. WP CMD: partner id mismatch"); - if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_REQUEST from ID %u because i'm already talking to ID %u.", msg->sysid, _wpm->current_partner_sysid); } + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: rejected, partner ID mismatch"); } } } - break; } @@ -1327,48 +1335,51 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE) { if (wpc.count > NUM_MISSIONS_SUPPORTED) { - if (_verbose) { warnx("Too many waypoints: %d, supported: %d", wpc.count, NUM_MISSIONS_SUPPORTED); } + if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: too many waypoints (%d), supported: %d", wpc.count, NUM_MISSIONS_SUPPORTED); } mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_NO_SPACE); break; } if (wpc.count == 0) { - mavlink_missionlib_send_gcs_string("COUNT 0"); - - if (_verbose) { warnx("got waypoint count of 0, clearing waypoint list and staying in state MAVLINK_WPM_STATE_IDLE"); } + if (_verbose) { warnx("WPM: MISSION_COUNT 0, clearing waypoints list and staying in state MAVLINK_WPM_STATE_IDLE"); } + mavlink_missionlib_send_gcs_string("WP COUNT 0: CLEAR MISSION"); break; } - if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) from %u changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid); } - - _wpm->current_state = MAVLINK_WPM_STATE_GETLIST; - _wpm->current_wp_id = 0; - _wpm->current_partner_sysid = msg->sysid; - _wpm->current_partner_compid = msg->compid; - _wpm->current_count = wpc.count; - - mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); + if (_verbose) { warnx("WPM: MISSION_COUNT %u from ID %u, changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid); } } else if (_wpm->current_state == MAVLINK_WPM_STATE_GETLIST) { if (_wpm->current_wp_id == 0) { - mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN"); + /* looks like our WAYPOINT_REQUEST was lost, try again */ + if (_verbose) { warnx("WPM: MISSION_COUNT %u (again) from ID %u", wpc.count, msg->sysid); } - if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) again from %u", wpc.count, msg->sysid); } + mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN"); } else { - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); + if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _wpm->current_wp_id); } - if (_verbose) { warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM_COUNT because i'm already receiving waypoint %u.", _wpm->current_wp_id); } + mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); + break; } } else { - mavlink_missionlib_send_gcs_string("IGN MISSION_COUNT CMD: Busy"); + if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, state %i", _wpm->current_state); } - if (_verbose) { warnx("IGN MISSION_COUNT CMD: Busy"); } + mavlink_missionlib_send_gcs_string("IGN MISSION_COUNT CMD: Busy"); + break; } + + _wpm->current_state = MAVLINK_WPM_STATE_GETLIST; + _wpm->current_wp_id = 0; + _wpm->current_partner_sysid = msg->sysid; + _wpm->current_partner_compid = msg->compid; + _wpm->current_count = wpc.count; + _wpm->current_dataman_id = _wpm->dataman_id == 0 ? 1 : 0; // use inactive storage for transmission + + mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); } } break; @@ -1378,32 +1389,28 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) mavlink_msg_mission_item_decode(msg, &wp); if (wp.target_system == mavlink_system.sysid && wp.target_component == _mavlink_wpm_comp_id) { - _wpm->timestamp_lastaction = now; - /* - * ensure that we are in the correct state and that the first waypoint has id 0 + /* Ensure that we are in the correct state and that the first waypoint has id 0 * and the following waypoints have the correct ids */ - if (_wpm->current_state == MAVLINK_WPM_STATE_GETLIST) { - if (wp.seq != 0) { - mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP not 0"); - warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the first waypoint ID (%u) was not 0.", wp.seq); + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: first item seq != 0 (%d)", wp.seq); } break; } } else if (_wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) { - if (wp.seq >= _wpm->current_count) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: first item seq %d out of bounds [0 %d]", wp.seq, _wpm->current_count - 1); } + mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP out of bounds"); - warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was out of bounds.", wp.seq); break; } if (wp.seq != _wpm->current_wp_id) { - warnx("Ignored MAVLINK_MSG_ID_MISSION_ITEM because the waypoint ID (%u) was not the expected %u.", wp.seq, _wpm->current_wp_id); + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u was not the expected %u", wp.seq, _wpm->current_wp_id); } + mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); break; } @@ -1412,86 +1419,92 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) _wpm->current_state = MAVLINK_WPM_STATE_GETLIST_GETWPS; struct mission_item_s mission_item; - int ret = map_mavlink_mission_item_to_mission_item(&wp, &mission_item); if (ret != OK) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq); } + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, ret); _wpm->current_state = MAVLINK_WPM_STATE_IDLE; break; } - ssize_t len = sizeof(struct mission_item_s); + dm_item_t dm_id = _wpm->current_dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; - dm_item_t dm_next; + if (dm_write(dm_id, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, sizeof(struct mission_item_s)) != sizeof(struct mission_item_s)) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, dm_id); } - if (_wpm->current_dataman_id == 0) { - dm_next = DM_KEY_WAYPOINTS_OFFBOARD_1; - mission.dataman_id = 1; - - } else { - dm_next = DM_KEY_WAYPOINTS_OFFBOARD_0; - mission.dataman_id = 0; - } - - if (dm_write(dm_next, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, len) != len) { mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD"); _wpm->current_state = MAVLINK_WPM_STATE_IDLE; break; } - // offboard mission data saved correctly, now update the persistent system state - { + + if (_verbose) { warnx("WPM: MISSION_ITEM seq %u received", wp.seq); } + + _wpm->current_wp_id = wp.seq + 1; + + if (_wpm->current_wp_id == _wpm->current_count && _wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) { + /* got all new mission items successfully */ + if (_verbose) { warnx("WPM: MISSION_ITEM got all %u items, changing state to MAVLINK_WPM_STATE_IDLE", _wpm->current_count); } + + _wpm->current_state = MAVLINK_WPM_STATE_IDLE; + + /* write terminator item */ + if (_wpm->current_count < _wpm->max_size) { + if (dm_write(dm_id, _wpm->current_count, DM_PERSIST_POWER_ON_RESET, nullptr, 0) != 0) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR writing terminator item"); } + + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); + break; + } + } + + /* offboard mission data saved correctly, now update the persistent system state */ persistent_system_state_t state; bool dm_result; - // Since we are doing a read-modify-write we must lock the item type + + /* since we are doing a read-modify-write we must lock the item type */ dm_lock(DM_KEY_SYSTEM_STATE); - // first read in the current state data. There may eventually be data other than the offboard index - // and we must preserve it - if (dm_read(DM_KEY_SYSTEM_STATE, 0, &state, sizeof(state)) != sizeof(state)) { - // Not sure how to handle this? It means that either the item was never - // written, or fields have been added to the system state struct. In any case - // fields that may not be ours need to be initialized to sane values. - // For now the offboard index is the only field, so for now there - // is nothing to do here. - } - state.current_offboard_waypoint_id = mission.dataman_id; - dm_result = dm_write(DM_KEY_SYSTEM_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) != sizeof(state); - dm_unlock(DM_KEY_SYSTEM_STATE); - if (dm_result) { - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); - mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD"); - _wpm->current_state = MAVLINK_WPM_STATE_IDLE; - break; - } - } + /* first read in the current state data, there may eventually be data other than the offboard index + * and we must preserve it */ + ssize_t dm_state_size = dm_read(DM_KEY_SYSTEM_STATE, 0, &state, sizeof(state)); + if (dm_state_size != sizeof(state)) { + warnx("dataman SYSTEM_STATE size invalid: %d, should be %d", dm_state_size, sizeof(state)); + } -// if (wp.current) { -// warnx("current is: %d", wp.seq); -// mission.current_index = wp.seq; -// } - // XXX ignore current set - mission.current_index = -1; + /* set new dataman storage ID */ + state.offboard_waypoint_id = _wpm->current_dataman_id; - _wpm->current_wp_id = wp.seq + 1; + /* write back to dataman */ + dm_result = dm_write(DM_KEY_SYSTEM_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) != sizeof(state); - if (_wpm->current_wp_id == _wpm->current_count && _wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) { + dm_unlock(DM_KEY_SYSTEM_STATE); - if (_verbose) { warnx("Got all %u waypoints, changing state to MAVLINK_WPM_STATE_IDLE", _wpm->current_count); } + if (dm_result) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR unable to write storage ID = %d to dataman SYSTEM_STATE", state.offboard_waypoint_id); } - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); + mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD"); - mission.count = _wpm->current_count; + } else { + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); - publish_mission(); + /* update WPM state */ + _wpm->dataman_id = _wpm->current_dataman_id; + _wpm->size = _wpm->current_count; - _wpm->current_dataman_id = mission.dataman_id; - _wpm->size = _wpm->current_count; + /* update mission topic */ + mission.dataman_id = _wpm->dataman_id; + mission.count = _wpm->current_count; + mission.current_index = 0; - _wpm->current_state = MAVLINK_WPM_STATE_IDLE; + publish_mission(); + } } else { + /* request next item */ mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); } } @@ -1506,46 +1519,34 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */) { if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE) { - _wpm->timestamp_lastaction = now; + /* clear only active dataman storage, don't change storage id */ + dm_item_t dm_id = _wpm->dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; - _wpm->size = 0; - - /* prepare mission topic */ - mission.dataman_id = -1; - mission.count = 0; - mission.current_index = -1; - publish_mission(); - - if (dm_clear(DM_KEY_WAYPOINTS_OFFBOARD_0) == OK && dm_clear(DM_KEY_WAYPOINTS_OFFBOARD_1) == OK) { - persistent_system_state_t state; - bool dm_result; - dm_lock(DM_KEY_SYSTEM_STATE); - // first read in the current state data. There may eventually be data other than the offboard index - // and we must preserve it - if (dm_read(DM_KEY_SYSTEM_STATE, 0, &state, sizeof(state)) != sizeof(state)) { - // Not sure how to handle this? It means that either the item was never - // written, or fields have been added to the system state struct. In any case - // fields that may not be ours need to be initialized to sane values. - // For now the offboard index is the only field, so we can deal with it here. - } - state.current_offboard_waypoint_id = -1; - dm_result = dm_write(DM_KEY_SYSTEM_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) == sizeof(state); - dm_unlock(DM_KEY_SYSTEM_STATE); - if (dm_result) { - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); - } else { - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); - } + if (dm_clear(dm_id) == OK) { + if (_verbose) { warnx("WPM: CLEAR_ALL OK"); } + + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); + + /* update WPM state */ + _wpm->timestamp_lastaction = now; + _wpm->size = 0; + + /* update mission topic */ + mission.count = 0; + mission.current_index = -1; + + publish_mission(); } else { + if (_verbose) { warnx("WPM: CLEAR_ALL ERROR: can't clear dataman mission storage"); } + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); } - } else { mavlink_missionlib_send_gcs_string("IGN WP CLEAR CMD: Busy"); - if (_verbose) { warnx("IGN WP CLEAR CMD: Busy"); } + if (_verbose) { warnx("WPM: CLEAR_ALL IGNORED: busy"); } } } @@ -1570,7 +1571,6 @@ Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg) } - int Mavlink::mavlink_missionlib_send_gcs_string(const char *string) { diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 40edc4b85..fbb25029d 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -84,18 +84,19 @@ enum MAVLINK_WPM_CODES { struct mavlink_wpm_storage { - uint16_t size; - uint16_t max_size; - enum MAVLINK_WPM_STATES current_state; - int16_t current_wp_id; ///< Waypoint in current transmission - uint16_t current_count; + uint16_t size; ///< Count of waypoints in active mission + uint16_t max_size; ///< Maximal count of waypoints + int dataman_id; ///< Dataman storage ID for active mission + enum MAVLINK_WPM_STATES current_state; ///< Current waypoint manager state + int16_t current_wp_id; ///< Waypoint ID in current transmission + uint16_t current_count; ///< Waypoints count in current transmission uint8_t current_partner_sysid; uint8_t current_partner_compid; + int current_dataman_id; ///< Dataman storage ID for current transmission uint64_t timestamp_lastaction; uint64_t timestamp_last_send_setpoint; uint64_t timestamp_last_send_request; uint32_t timeout; - int current_dataman_id; }; diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 04ea7da0e..a3426e65e 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -603,14 +603,12 @@ Navigator::task_main() warnx("Could not clear geofence"); } -#if 0 // *** UNTESTED... Anton, this is for you /* Get the last offboard mission id */ persistent_system_state_t sys_state; if (dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state)) == sizeof(sys_state)) { - if ((sys_state.current_offboard_waypoint_id >= 0) && (sys_state.current_offboard_waypoint_id <= 1)) - _mission.set_offboard_dataman_id(sys_state.current_offboard_waypoint_id); + if ((sys_state.offboard_waypoint_id >= 0) && (sys_state.offboard_waypoint_id <= 1)) + _mission.set_offboard_dataman_id(sys_state.offboard_waypoint_id); } -#endif /* * do subscriptions diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h index ef4bc1def..5f3cbcb1d 100644 --- a/src/modules/uORB/topics/mission.h +++ b/src/modules/uORB/topics/mission.h @@ -95,8 +95,8 @@ struct mission_item_s { struct mission_s { - int dataman_id; /**< default -1, there are two offboard storage places in the dataman: 0 or 1 */ - unsigned count; /**< count of the missions stored in the datamanager */ + int dataman_id; /**< default 0, there are two offboard storage places in the dataman: 0 or 1 */ + unsigned count; /**< count of the missions stored in the dataman */ int current_index; /**< default -1, start at the one changed latest */ }; -- cgit v1.2.3 From d9b5efb263b61b8dc47ee63d7b4eb0b62853877a Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Mon, 9 Jun 2014 19:09:38 -0400 Subject: Closed additional file descriptor --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 6a105762b..9d9d2a7c0 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -1071,6 +1071,12 @@ MulticopterPositionControl::task_main() _reset_pos_sp = true; reset_int_z = true; reset_int_xy = true; + + /* Close att_sp pub to allow offboard mode or att controller to advertise */ + if (_att_sp_pub > 0) { + close(_att_sp_pub); + _att_sp_pub = -1; + } } /* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */ -- cgit v1.2.3 From 3015f2e7af94e684c666689aa70c602f79810218 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 10 Jun 2014 14:32:37 +0200 Subject: mavlink: retry timeout moved to define --- src/modules/mavlink/mavlink_main.cpp | 7 ++++--- src/modules/mavlink/mavlink_main.h | 8 +++++--- src/modules/mavlink/waypoints.h | 2 +- 3 files changed, 10 insertions(+), 7 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 4e0597e80..52cae2085 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -965,7 +965,8 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) state->timestamp_lastaction = 0; state->timestamp_last_send_setpoint = 0; state->timestamp_last_send_request = 0; - state->timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; + state->action_timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; + state->retry_timeout = MAVLINK_WPM_RETRY_TIMEOUT_DEFAULT; int sys_state_size = dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state)); if (sys_state_size == sizeof(sys_state)) { @@ -1138,7 +1139,7 @@ void Mavlink::mavlink_wpm_send_waypoint_reached(uint16_t seq) void Mavlink::mavlink_waypoint_eventloop(uint64_t now) { /* check for timed-out operations */ - if (now - _wpm->timestamp_lastaction > _wpm->timeout && _wpm->current_state != MAVLINK_WPM_STATE_IDLE) { + if (now - _wpm->timestamp_lastaction > _wpm->action_timeout && _wpm->current_state != MAVLINK_WPM_STATE_IDLE) { mavlink_missionlib_send_gcs_string("Operation timeout"); @@ -1148,7 +1149,7 @@ void Mavlink::mavlink_waypoint_eventloop(uint64_t now) _wpm->current_partner_sysid = 0; _wpm->current_partner_compid = 0; - } else if (now - _wpm->timestamp_last_send_request > 500000 && _wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) { + } else if (now - _wpm->timestamp_last_send_request > _wpm->retry_timeout && _wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) { /* try to get WP again after short timeout */ mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); } diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index fbb25029d..e31bbbb31 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -78,8 +78,9 @@ enum MAVLINK_WPM_CODES { #define MAVLINK_WPM_MAX_WP_COUNT 255 -#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication timeout in useconds -#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000000 ///< When to send a new setpoint +#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication action timeout in useconds +#define MAVLINK_WPM_RETRY_TIMEOUT_DEFAULT 500000 ///< Protocol communication retry timeout in useconds +#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000000 ///< When to send a new setpoint #define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40000 @@ -96,7 +97,8 @@ struct mavlink_wpm_storage { uint64_t timestamp_lastaction; uint64_t timestamp_last_send_setpoint; uint64_t timestamp_last_send_request; - uint32_t timeout; + uint32_t action_timeout; + uint32_t retry_timeout; }; diff --git a/src/modules/mavlink/waypoints.h b/src/modules/mavlink/waypoints.h index 532eff7aa..a2109f2d8 100644 --- a/src/modules/mavlink/waypoints.h +++ b/src/modules/mavlink/waypoints.h @@ -88,7 +88,7 @@ struct mavlink_wpm_storage { uint8_t current_partner_compid; uint64_t timestamp_lastaction; uint64_t timestamp_last_send_setpoint; - uint32_t timeout; + uint32_t action_timeout; int current_dataman_id; }; -- cgit v1.2.3 From 578680135e6813151a791dbcc3c31b1ba9c31a97 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:03:58 +0200 Subject: introduce multi device support on uORB --- src/drivers/drv_accel.h | 3 ++- src/drivers/drv_baro.h | 3 ++- src/drivers/drv_gyro.h | 3 ++- src/drivers/drv_mag.h | 3 ++- src/modules/uORB/objects_common.cpp | 12 ++++++++---- 5 files changed, 16 insertions(+), 8 deletions(-) diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h index 7d93ed938..a6abaec70 100644 --- a/src/drivers/drv_accel.h +++ b/src/drivers/drv_accel.h @@ -81,7 +81,8 @@ struct accel_scale { /* * ObjDev tag for raw accelerometer data. */ -ORB_DECLARE(sensor_accel); +ORB_DECLARE(sensor_accel0); +ORB_DECLARE(sensor_accel1); /* * ioctl() definitions diff --git a/src/drivers/drv_baro.h b/src/drivers/drv_baro.h index e2f0137ae..248b9a73d 100644 --- a/src/drivers/drv_baro.h +++ b/src/drivers/drv_baro.h @@ -63,7 +63,8 @@ struct baro_report { /* * ObjDev tag for raw barometer data. */ -ORB_DECLARE(sensor_baro); +ORB_DECLARE(sensor_baro0); +ORB_DECLARE(sensor_baro1); /* * ioctl() definitions diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h index 2ae8c7058..3635cbce1 100644 --- a/src/drivers/drv_gyro.h +++ b/src/drivers/drv_gyro.h @@ -81,7 +81,8 @@ struct gyro_scale { /* * ObjDev tag for raw gyro data. */ -ORB_DECLARE(sensor_gyro); +ORB_DECLARE(sensor_gyro0); +ORB_DECLARE(sensor_gyro1); /* * ioctl() definitions diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h index 06107bd3d..32e0e48b3 100644 --- a/src/drivers/drv_mag.h +++ b/src/drivers/drv_mag.h @@ -79,7 +79,8 @@ struct mag_scale { /* * ObjDev tag for raw magnetometer data. */ -ORB_DECLARE(sensor_mag); +ORB_DECLARE(sensor_mag0); +ORB_DECLARE(sensor_mag1); /* * ioctl() definitions diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp index 90675bb2e..8340ca28a 100644 --- a/src/modules/uORB/objects_common.cpp +++ b/src/modules/uORB/objects_common.cpp @@ -46,16 +46,20 @@ #include #include -ORB_DEFINE(sensor_mag, struct mag_report); +ORB_DEFINE(sensor_mag0, struct mag_report); +ORB_DEFINE(sensor_mag1, struct mag_report); #include -ORB_DEFINE(sensor_accel, struct accel_report); +ORB_DEFINE(sensor_accel0, struct accel_report); +ORB_DEFINE(sensor_accel1, struct accel_report); #include -ORB_DEFINE(sensor_gyro, struct gyro_report); +ORB_DEFINE(sensor_gyro0, struct gyro_report); +ORB_DEFINE(sensor_gyro1, struct gyro_report); #include -ORB_DEFINE(sensor_baro, struct baro_report); +ORB_DEFINE(sensor_baro0, struct baro_report); +ORB_DEFINE(sensor_baro1, struct baro_report); #include ORB_DEFINE(sensor_range_finder, struct range_finder_report); -- cgit v1.2.3 From 96accbf96cbc0262e4bb815d722282a318e8b8c5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:04:18 +0200 Subject: Make sensors app multi-device aware --- src/modules/sensors/sensors.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index b268b1b36..0ae93d7f0 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -967,7 +967,7 @@ Sensors::accel_poll(struct sensor_combined_s &raw) if (accel_updated) { struct accel_report accel_report; - orb_copy(ORB_ID(sensor_accel), _accel_sub, &accel_report); + orb_copy(ORB_ID(sensor_accel0), _accel_sub, &accel_report); math::Vector<3> vect(accel_report.x, accel_report.y, accel_report.z); vect = _board_rotation * vect; @@ -993,7 +993,7 @@ Sensors::gyro_poll(struct sensor_combined_s &raw) if (gyro_updated) { struct gyro_report gyro_report; - orb_copy(ORB_ID(sensor_gyro), _gyro_sub, &gyro_report); + orb_copy(ORB_ID(sensor_gyro0), _gyro_sub, &gyro_report); math::Vector<3> vect(gyro_report.x, gyro_report.y, gyro_report.z); vect = _board_rotation * vect; @@ -1019,7 +1019,7 @@ Sensors::mag_poll(struct sensor_combined_s &raw) if (mag_updated) { struct mag_report mag_report; - orb_copy(ORB_ID(sensor_mag), _mag_sub, &mag_report); + orb_copy(ORB_ID(sensor_mag0), _mag_sub, &mag_report); math::Vector<3> vect(mag_report.x, mag_report.y, mag_report.z); @@ -1050,7 +1050,7 @@ Sensors::baro_poll(struct sensor_combined_s &raw) if (baro_updated) { - orb_copy(ORB_ID(sensor_baro), _baro_sub, &_barometer); + orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_barometer); raw.baro_pres_mbar = _barometer.pressure; // Pressure in mbar raw.baro_alt_meter = _barometer.altitude; // Altitude in meters @@ -1579,11 +1579,11 @@ Sensors::task_main() /* * do subscriptions */ - _gyro_sub = orb_subscribe(ORB_ID(sensor_gyro)); - _accel_sub = orb_subscribe(ORB_ID(sensor_accel)); - _mag_sub = orb_subscribe(ORB_ID(sensor_mag)); + _gyro_sub = orb_subscribe(ORB_ID(sensor_gyro0)); + _accel_sub = orb_subscribe(ORB_ID(sensor_accel0)); + _mag_sub = orb_subscribe(ORB_ID(sensor_mag0)); _rc_sub = orb_subscribe(ORB_ID(input_rc)); - _baro_sub = orb_subscribe(ORB_ID(sensor_baro)); + _baro_sub = orb_subscribe(ORB_ID(sensor_baro0)); _diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); _vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); -- cgit v1.2.3 From 07fb1e089d1d15d512a8a68b03020b1ffd877ed3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:04:56 +0200 Subject: Make commander multi-device aware --- src/modules/commander/gyro_calibration.cpp | 4 ++-- src/modules/commander/mag_calibration.cpp | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp index cbc2844c1..d89c67c2b 100644 --- a/src/modules/commander/gyro_calibration.cpp +++ b/src/modules/commander/gyro_calibration.cpp @@ -92,7 +92,7 @@ int do_gyro_calibration(int mavlink_fd) unsigned poll_errcount = 0; /* subscribe to gyro sensor topic */ - int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro)); + int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro0)); struct gyro_report gyro_report; while (calibration_counter < calibration_count) { @@ -104,7 +104,7 @@ int do_gyro_calibration(int mavlink_fd) int poll_ret = poll(fds, 1, 1000); if (poll_ret > 0) { - orb_copy(ORB_ID(sensor_gyro), sub_sensor_gyro, &gyro_report); + orb_copy(ORB_ID(sensor_gyro0), sub_sensor_gyro, &gyro_report); gyro_scale.x_offset += gyro_report.x; gyro_scale.y_offset += gyro_report.y; gyro_scale.z_offset += gyro_report.z; diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index 0ead22f77..23900f386 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -145,7 +145,7 @@ int do_mag_calibration(int mavlink_fd) } if (res == OK) { - int sub_mag = orb_subscribe(ORB_ID(sensor_mag)); + int sub_mag = orb_subscribe(ORB_ID(sensor_mag0)); struct mag_report mag; /* limit update rate to get equally spaced measurements over time (in ms) */ @@ -170,7 +170,7 @@ int do_mag_calibration(int mavlink_fd) int poll_ret = poll(fds, 1, 1000); if (poll_ret > 0) { - orb_copy(ORB_ID(sensor_mag), sub_mag, &mag); + orb_copy(ORB_ID(sensor_mag0), sub_mag, &mag); x[calibration_counter] = mag.x; y[calibration_counter] = mag.y; -- cgit v1.2.3 From a2ef04146aa5eb233fd564f38e447e983e5985a7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:05:22 +0200 Subject: Introduce enum / define for multiple devices --- src/drivers/device/device.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h index d99f22922..be6f6f4ec 100644 --- a/src/drivers/device/device.h +++ b/src/drivers/device/device.h @@ -510,6 +510,9 @@ private: } // namespace device // class instance for primary driver of each class -#define CLASS_DEVICE_PRIMARY 0 +enum CLASS_DEVICE { + CLASS_DEVICE_PRIMARY=0, + CLASS_DEVICE_SECONDARY=1 +}; #endif /* _DEVICE_DEVICE_H */ -- cgit v1.2.3 From dc2df309cba57a754b291b528f92d252fc271f57 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:05:50 +0200 Subject: Introduce HMC5883 multi-device support --- src/drivers/hmc5883/hmc5883.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index fddba806e..be8e14807 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -866,9 +866,9 @@ HMC5883::collect() if (_mag_topic != -1) { /* publish it */ - orb_publish(ORB_ID(sensor_mag), _mag_topic, &new_report); + orb_publish(ORB_ID(sensor_mag0), _mag_topic, &new_report); } else { - _mag_topic = orb_advertise(ORB_ID(sensor_mag), &new_report); + _mag_topic = orb_advertise(ORB_ID(sensor_mag0), &new_report); if (_mag_topic < 0) debug("failed to create sensor_mag publication"); -- cgit v1.2.3 From 506f900513c1ce319a0160f8ac82a399274ac66f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:06:05 +0200 Subject: Introduce MPU6K multi-device uORB support --- src/drivers/mpu6000/mpu6000.cpp | 71 +++++++++++++++++++++++++++++------------ 1 file changed, 50 insertions(+), 21 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 321fdd173..10966e2d0 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -491,31 +491,44 @@ MPU6000::init() measure(); - if (_accel_class_instance == CLASS_DEVICE_PRIMARY) { - - /* advertise sensor topic, measure manually to initialize valid report */ - struct accel_report arp; - _accel_reports->get(&arp); - - /* measurement will have generated a report, publish */ - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp); + /* advertise sensor topic, measure manually to initialize valid report */ + struct accel_report arp; + _accel_reports->get(&arp); + + /* measurement will have generated a report, publish */ + switch (_accel_class_instance) { + case CLASS_DEVICE_PRIMARY: + _accel_topic = orb_advertise(ORB_ID(sensor_accel0), &arp); + break; + + case CLASS_DEVICE_SECONDARY: + _accel_topic = orb_advertise(ORB_ID(sensor_accel1), &arp); + break; - if (_accel_topic < 0) - debug("failed to create sensor_accel publication"); + } + if (_accel_topic < 0) { + warnx("failed to create sensor_accel publication"); } - if (_gyro->_gyro_class_instance == CLASS_DEVICE_PRIMARY) { - /* advertise sensor topic, measure manually to initialize valid report */ - struct gyro_report grp; - _gyro_reports->get(&grp); + /* advertise sensor topic, measure manually to initialize valid report */ + struct gyro_report grp; + _gyro_reports->get(&grp); - _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp); + switch (_gyro->_gyro_class_instance) { + case CLASS_DEVICE_PRIMARY: + _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro0), &grp); + break; + + case CLASS_DEVICE_SECONDARY: + _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro1), &grp); + break; - if (_gyro->_gyro_topic < 0) - debug("failed to create sensor_gyro publication"); + } + if (_gyro->_gyro_topic < 0) { + warnx("failed to create sensor_gyro publication"); } out: @@ -1326,14 +1339,30 @@ MPU6000::measure() poll_notify(POLLIN); _gyro->parent_poll_notify(); - if (_accel_topic > 0 && !(_pub_blocked)) { + if (!(_pub_blocked)) { /* publish it */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, &arb); + switch (_accel_class_instance) { + case CLASS_DEVICE_PRIMARY: + orb_publish(ORB_ID(sensor_accel0), _accel_topic, &arb); + break; + + case CLASS_DEVICE_SECONDARY: + orb_publish(ORB_ID(sensor_accel1), _accel_topic, &arb); + break; + } } - if (_gyro->_gyro_topic > 0 && !(_pub_blocked)) { + if (!(_pub_blocked)) { /* publish it */ - orb_publish(ORB_ID(sensor_gyro), _gyro->_gyro_topic, &grb); + switch (_gyro->_gyro_class_instance) { + case CLASS_DEVICE_PRIMARY: + orb_publish(ORB_ID(sensor_gyro0), _gyro->_gyro_topic, &grb); + break; + + case CLASS_DEVICE_SECONDARY: + orb_publish(ORB_ID(sensor_gyro1), _gyro->_gyro_topic, &grb); + break; + } } /* stop measuring */ -- cgit v1.2.3 From 795f3693f26f1671a417cb7b6e36d743cab72304 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:07:42 +0200 Subject: LSM303D: Add support for multi-uORB devices --- src/drivers/lsm303d/lsm303d.cpp | 73 ++++++++++++++++++++++++++++------------- 1 file changed, 50 insertions(+), 23 deletions(-) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 8bf76dcc3..8a14aca4b 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -600,34 +600,45 @@ LSM303D::init() /* fill report structures */ measure(); - if (_mag->_mag_class_instance == CLASS_DEVICE_PRIMARY) { - - /* advertise sensor topic, measure manually to initialize valid report */ - struct mag_report mrp; - _mag_reports->get(&mrp); - - /* measurement will have generated a report, publish */ - _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag), &mrp); - - if (_mag->_mag_topic < 0) - debug("failed to create sensor_mag publication"); + /* advertise sensor topic, measure manually to initialize valid report */ + struct mag_report mrp; + _mag_reports->get(&mrp); + + /* measurement will have generated a report, publish */ + switch (_mag->_mag_class_instance) { + case CLASS_DEVICE_PRIMARY: + _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag0), &mrp); + break; + + case CLASS_DEVICE_SECONDARY: + _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag1), &mrp); + break; + } + if (_mag->_mag_topic < 0) { + warnx("failed to create sensor_mag publication"); } _accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH); - if (_accel_class_instance == CLASS_DEVICE_PRIMARY) { + /* advertise sensor topic, measure manually to initialize valid report */ + struct accel_report arp; + _accel_reports->get(&arp); - /* advertise sensor topic, measure manually to initialize valid report */ - struct accel_report arp; - _accel_reports->get(&arp); + /* measurement will have generated a report, publish */ + switch (_accel_class_instance) { + case CLASS_DEVICE_PRIMARY: + _accel_topic = orb_advertise(ORB_ID(sensor_accel0), &arp); + break; - /* measurement will have generated a report, publish */ - _accel_topic = orb_advertise(ORB_ID(sensor_accel), &arp); + case CLASS_DEVICE_SECONDARY: + _accel_topic = orb_advertise(ORB_ID(sensor_accel1), &arp); + break; - if (_accel_topic < 0) - debug("failed to create sensor_accel publication"); + } + if (_accel_topic < 0) { + warnx("failed to create sensor_accel publication"); } out: @@ -1541,9 +1552,17 @@ LSM303D::measure() /* notify anyone waiting for data */ poll_notify(POLLIN); - if (_accel_topic > 0 && !(_pub_blocked)) { + if (!(_pub_blocked)) { /* publish it */ - orb_publish(ORB_ID(sensor_accel), _accel_topic, &accel_report); + switch (_accel_class_instance) { + case CLASS_DEVICE_PRIMARY: + orb_publish(ORB_ID(sensor_accel0), _accel_topic, &accel_report); + break; + + case CLASS_DEVICE_SECONDARY: + orb_publish(ORB_ID(sensor_accel1), _accel_topic, &accel_report); + break; + } } _accel_read++; @@ -1615,9 +1634,17 @@ LSM303D::mag_measure() /* notify anyone waiting for data */ poll_notify(POLLIN); - if (_mag->_mag_topic > 0 && !(_pub_blocked)) { + if (!(_pub_blocked)) { /* publish it */ - orb_publish(ORB_ID(sensor_mag), _mag->_mag_topic, &mag_report); + switch (_mag->_mag_class_instance) { + case CLASS_DEVICE_PRIMARY: + orb_publish(ORB_ID(sensor_mag0), _mag->_mag_topic, &mag_report); + break; + + case CLASS_DEVICE_SECONDARY: + orb_publish(ORB_ID(sensor_mag1), _mag->_mag_topic, &mag_report); + break; + } } _mag_read++; -- cgit v1.2.3 From c35a25e70a57229b58fe065fda23003de856e9f5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:08:21 +0200 Subject: L3GD20: Add support for multi uORB topics --- src/drivers/l3gd20/l3gd20.cpp | 30 ++++++++++++++++++++---------- 1 file changed, 20 insertions(+), 10 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 37e72388b..2fcbdc0ad 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -398,17 +398,19 @@ L3GD20::init() measure(); - if (_class_instance == CLASS_DEVICE_PRIMARY) { - - /* advertise sensor topic, measure manually to initialize valid report */ - struct gyro_report grp; - _reports->get(&grp); + /* advertise sensor topic, measure manually to initialize valid report */ + struct gyro_report grp; + _reports->get(&grp); - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro), &grp); + if (_class_instance == CLASS_DEVICE_PRIMARY) { + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro0), &grp); - if (_gyro_topic < 0) - debug("failed to create sensor_gyro publication"); + } else if (_class_instance == CLASS_DEVICE_SECONDARY) { + _gyro_topic = orb_advertise(ORB_ID(sensor_gyro1), &grp); + } + if (_gyro_topic < 0) { + debug("failed to create sensor_gyro publication"); } ret = OK; @@ -923,9 +925,17 @@ L3GD20::measure() poll_notify(POLLIN); /* publish for subscribers */ - if (_gyro_topic > 0 && !(_pub_blocked)) { + if (!(_pub_blocked)) { /* publish it */ - orb_publish(ORB_ID(sensor_gyro), _gyro_topic, &report); + switch (_class_instance) { + case CLASS_DEVICE_PRIMARY: + orb_publish(ORB_ID(sensor_gyro0), _gyro_topic, &report); + break; + + case CLASS_DEVICE_SECONDARY: + orb_publish(ORB_ID(sensor_gyro1), _gyro_topic, &report); + break; + } } _read++; -- cgit v1.2.3 From becfed9fbd93204134c44f6da09d954151dff10d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:08:47 +0200 Subject: MS5611: Add support for multi uORB devices --- src/drivers/ms5611/ms5611.cpp | 27 ++++++++++++++++++++------- 1 file changed, 20 insertions(+), 7 deletions(-) diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp index 1ce93aeea..2d85a5e0d 100644 --- a/src/drivers/ms5611/ms5611.cpp +++ b/src/drivers/ms5611/ms5611.cpp @@ -299,12 +299,17 @@ MS5611::init() ret = OK; - if (_class_instance == CLASS_DEVICE_PRIMARY) { - - _baro_topic = orb_advertise(ORB_ID(sensor_baro), &brp); + switch (_class_instance) { + case CLASS_DEVICE_PRIMARY: + _baro_topic = orb_advertise(ORB_ID(sensor_baro0), &brp); + break; + case CLASS_DEVICE_SECONDARY: + _baro_topic = orb_advertise(ORB_ID(sensor_baro1), &brp); + break; + } - if (_baro_topic < 0) - debug("failed to create sensor_baro publication"); + if (_baro_topic < 0) { + warnx("failed to create sensor_baro publication"); } } while (0); @@ -721,9 +726,17 @@ MS5611::collect() report.altitude = (((pow((p / p1), (-(a * R) / g))) * T1) - T1) / a; /* publish it */ - if (_baro_topic > 0 && !(_pub_blocked)) { + if (!(_pub_blocked)) { /* publish it */ - orb_publish(ORB_ID(sensor_baro), _baro_topic, &report); + switch (_class_instance) { + case CLASS_DEVICE_PRIMARY: + orb_publish(ORB_ID(sensor_baro0), _baro_topic, &report); + break; + + case CLASS_DEVICE_SECONDARY: + orb_publish(ORB_ID(sensor_baro1), _baro_topic, &report); + break; + } } if (_reports->force(&report)) { -- cgit v1.2.3 From 699ad1512cb55db004ab7d7143dd1ef8741fb9ad Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:09:16 +0200 Subject: EKF estimator: Add support for multi uORB sensor topics --- src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index 0a6d3fa8f..d806b0241 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -522,7 +522,7 @@ FixedwingEstimator::task_main() /* * do subscriptions */ - _baro_sub = orb_subscribe(ORB_ID(sensor_baro)); + _baro_sub = orb_subscribe(ORB_ID(sensor_baro0)); _airspeed_sub = orb_subscribe(ORB_ID(airspeed)); _gps_sub = orb_subscribe(ORB_ID(vehicle_gps_position)); _vstatus_sub = orb_subscribe(ORB_ID(vehicle_status)); @@ -861,7 +861,7 @@ FixedwingEstimator::task_main() orb_check(_baro_sub, &baro_updated); if (baro_updated) { - orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro); + orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_baro); _ekf->baroHgt = _baro.altitude; @@ -1040,7 +1040,7 @@ FixedwingEstimator::task_main() float gps_alt = _gps.alt / 1e3f; // Set up height correctly - orb_copy(ORB_ID(sensor_baro), _baro_sub, &_baro); + orb_copy(ORB_ID(sensor_baro0), _baro_sub, &_baro); _baro_gps_offset = _baro_ref - _baro.altitude; _ekf->baroHgt = _baro.altitude; _ekf->hgtMea = 1.0f * (_ekf->baroHgt - (_baro_ref)); -- cgit v1.2.3 From e3e8bf25befa23edd6e2963760794abf4c8d6e2e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:09:41 +0200 Subject: FW att control: Add support for multi uORB topics --- src/modules/fw_att_control/fw_att_control_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp index 178b590ae..c026e29a7 100644 --- a/src/modules/fw_att_control/fw_att_control_main.cpp +++ b/src/modules/fw_att_control/fw_att_control_main.cpp @@ -520,7 +520,7 @@ FixedwingAttitudeControl::vehicle_accel_poll() orb_check(_accel_sub, &accel_updated); if (accel_updated) { - orb_copy(ORB_ID(sensor_accel), _accel_sub, &_accel); + orb_copy(ORB_ID(sensor_accel0), _accel_sub, &_accel); } } @@ -568,7 +568,7 @@ FixedwingAttitudeControl::task_main() */ _att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint)); _att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); - _accel_sub = orb_subscribe(ORB_ID(sensor_accel)); + _accel_sub = orb_subscribe(ORB_ID(sensor_accel0)); _airspeed_sub = orb_subscribe(ORB_ID(airspeed)); _vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode)); _params_sub = orb_subscribe(ORB_ID(parameter_update)); -- cgit v1.2.3 From 0031713004dc9dcc071e13ee388af8ad028d3978 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:10:12 +0200 Subject: mavlink: Add support for multi uORB sensor interface --- src/modules/mavlink/mavlink_receiver.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 53769e0cf..98a7cef5a 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -495,10 +495,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) gyro.temperature = imu.temperature; if (_gyro_pub < 0) { - _gyro_pub = orb_advertise(ORB_ID(sensor_gyro), &gyro); + _gyro_pub = orb_advertise(ORB_ID(sensor_gyro0), &gyro); } else { - orb_publish(ORB_ID(sensor_gyro), _gyro_pub, &gyro); + orb_publish(ORB_ID(sensor_gyro0), _gyro_pub, &gyro); } } @@ -517,10 +517,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) accel.temperature = imu.temperature; if (_accel_pub < 0) { - _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel); + _accel_pub = orb_advertise(ORB_ID(sensor_accel0), &accel); } else { - orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel); + orb_publish(ORB_ID(sensor_accel0), _accel_pub, &accel); } } @@ -538,10 +538,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) mag.z = imu.zmag; if (_mag_pub < 0) { - _mag_pub = orb_advertise(ORB_ID(sensor_mag), &mag); + _mag_pub = orb_advertise(ORB_ID(sensor_mag0), &mag); } else { - orb_publish(ORB_ID(sensor_mag), _mag_pub, &mag); + orb_publish(ORB_ID(sensor_mag0), _mag_pub, &mag); } } @@ -556,10 +556,10 @@ MavlinkReceiver::handle_message_hil_sensor(mavlink_message_t *msg) baro.temperature = imu.temperature; if (_baro_pub < 0) { - _baro_pub = orb_advertise(ORB_ID(sensor_baro), &baro); + _baro_pub = orb_advertise(ORB_ID(sensor_baro0), &baro); } else { - orb_publish(ORB_ID(sensor_baro), _baro_pub, &baro); + orb_publish(ORB_ID(sensor_baro0), _baro_pub, &baro); } } @@ -835,10 +835,10 @@ MavlinkReceiver::handle_message_hil_state_quaternion(mavlink_message_t *msg) accel.temperature = 25.0f; if (_accel_pub < 0) { - _accel_pub = orb_advertise(ORB_ID(sensor_accel), &accel); + _accel_pub = orb_advertise(ORB_ID(sensor_accel0), &accel); } else { - orb_publish(ORB_ID(sensor_accel), _accel_pub, &accel); + orb_publish(ORB_ID(sensor_accel0), _accel_pub, &accel); } } -- cgit v1.2.3 From d0f4232ac6e2ff9d796df9d995e749734edc32ee Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:12:11 +0200 Subject: Build and runtime fixes for matlab csv serial bridge --- src/examples/matlab_csv_serial/matlab_csv_serial.c | 51 +++++++++++----------- src/examples/matlab_csv_serial/module.mk | 3 +- 2 files changed, 27 insertions(+), 27 deletions(-) diff --git a/src/examples/matlab_csv_serial/matlab_csv_serial.c b/src/examples/matlab_csv_serial/matlab_csv_serial.c index 7c8bcc31e..1327d1a23 100644 --- a/src/examples/matlab_csv_serial/matlab_csv_serial.c +++ b/src/examples/matlab_csv_serial/matlab_csv_serial.c @@ -95,7 +95,7 @@ int matlab_csv_serial_main(int argc, char *argv[]) { if (thread_running) { - printf("flow position estimator already running\n"); + warnx("already running\n"); /* this is not an error */ exit(0); } @@ -133,19 +133,21 @@ int matlab_csv_serial_main(int argc, char *argv[]) int matlab_csv_serial_thread_main(int argc, char *argv[]) { - /* welcome user */ - thread_running = true; if (argc < 2) { errx(1, "need a serial port name as argument"); } - int serial_fd = open(argv[1], O_RDWR | O_NOCTTY); + const char* uart_name = argv[1]; + + warnx("opening port %s", uart_name); + + int serial_fd = open(uart_name, O_RDWR | O_NOCTTY); unsigned speed = 921600; if (serial_fd < 0) { - err(1, "failed to open port: %s", argv[1]); + err(1, "failed to open port: %s", uart_name); } /* Try to set baud rate */ @@ -154,15 +156,12 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) bool is_usb = false; /* Back up the original uart configuration to restore it after exit */ - if ((termios_state = tcgetattr(_uart_fd, uart_config_original)) < 0) { + if ((termios_state = tcgetattr(serial_fd, &uart_config)) < 0) { warnx("ERR GET CONF %s: %d\n", uart_name, termios_state); - close(_uart_fd); + close(serial_fd); return -1; } - /* Fill the struct for the new configuration */ - tcgetattr(_uart_fd, &uart_config); - /* Clear ONLCR flag (which appends a CR for every LF) */ uart_config.c_oflag &= ~ONLCR; @@ -171,7 +170,7 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) /* Set baud rate */ if (cfsetispeed(&uart_config, speed) < 0 || cfsetospeed(&uart_config, speed) < 0) { - warnx("ERR SET BAUD %s: %d\n", argv[1], termios_state); + warnx("ERR SET BAUD %s: %d\n", uart_name, termios_state); close(serial_fd); return -1; } @@ -179,7 +178,7 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) } if ((termios_state = tcsetattr(serial_fd, TCSANOW, &uart_config)) < 0) { - warnx("ERR SET CONF %s\n", argv[1]); + warnx("ERR SET CONF %s\n", uart_name); close(serial_fd); return -1; } @@ -191,20 +190,19 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) struct gyro_report gyro1; /* subscribe to parameter changes */ - int accel0_sub = orb_subscribe(ORB_ID(sensor_accel)); - int accel1_sub; - int gyro0_sub; - int gyro1_sub; + int accel0_sub = orb_subscribe(ORB_ID(sensor_accel0)); + int accel1_sub = orb_subscribe(ORB_ID(sensor_accel1)); + int gyro0_sub = orb_subscribe(ORB_ID(sensor_gyro0)); + int gyro1_sub = orb_subscribe(ORB_ID(sensor_gyro1)); + + thread_running = true; while (!thread_should_exit) { /*This runs at the rate of the sensors */ struct pollfd fds[] = { - { .fd = accel0_sub, .events = POLLIN }, - { .fd = accel1_sub, .events = POLLIN }, - { .fd = gyro0_sub, .events = POLLIN }, - { .fd = gyro1_sub, .events = POLLIN } + { .fd = accel0_sub, .events = POLLIN } }; /* wait for a sensor update, check for exit condition every 500 ms */ @@ -212,8 +210,7 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) if (ret < 0) { - /* poll error, count it in perf */ - perf_count(mc_err_perf); + /* poll error, ignore */ } else if (ret == 0) @@ -224,13 +221,17 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) else { - /* parameter update available? */ + /* accel0 update available? */ if (fds[0].revents & POLLIN) { - orb_copy(ORB_ID(sensor_accel), accel0_sub, &accel0); + orb_copy(ORB_ID(sensor_accel0), accel0_sub, &accel0); + orb_copy(ORB_ID(sensor_accel1), accel0_sub, &accel1); + orb_copy(ORB_ID(sensor_gyro0), gyro0_sub, &gyro0); + orb_copy(ORB_ID(sensor_gyro1), gyro1_sub, &gyro1); // write out on accel 0, but collect for all other sensors as they have updates - vdprintf(serial_fd, "%llu,%d\n", accel0.timestamp, (int)accel0.x_raw); + dprintf(serial_fd, "%llu,%d,%d,%d,%d,%d,%d\n", accel0.timestamp, (int)accel0.x_raw, (int)accel0.y_raw, (int)accel0.z_raw, + (int)accel1.x_raw, (int)accel1.y_raw, (int)accel1.z_raw); } } diff --git a/src/examples/matlab_csv_serial/module.mk b/src/examples/matlab_csv_serial/module.mk index c83d1fefd..1629c2ce4 100644 --- a/src/examples/matlab_csv_serial/module.mk +++ b/src/examples/matlab_csv_serial/module.mk @@ -37,5 +37,4 @@ MODULE_COMMAND = matlab_csv_serial -SRCS = matlab_csv_serial.c \ - matlab_csv_serial.c +SRCS = matlab_csv_serial.c -- cgit v1.2.3 From 474de62ebb825de8d3757730fc3bdf8af250e173 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Jun 2014 15:12:23 +0200 Subject: Enable matlab bridge in test setup --- makefiles/config_px4fmu-v2_test.mk | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk index 66b2157ed..119056a39 100644 --- a/makefiles/config_px4fmu-v2_test.mk +++ b/makefiles/config_px4fmu-v2_test.mk @@ -32,6 +32,11 @@ MODULES += systemcmds/nshterm MODULES += systemcmds/mtd MODULES += systemcmds/ver +# +# Testing modules +# +MODULES += examples/matlab_csv_serial + # # Library modules # -- cgit v1.2.3 From ca6463efd816a6bb01bf0ff54260e2fef33e1d84 Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Tue, 10 Jun 2014 19:24:03 -0400 Subject: Modified mavlink receiver to scale offboard position and velocity messages to centimeters --- src/modules/mavlink/mavlink_receiver.cpp | 27 ++++++++++++++++++++++----- 1 file changed, 22 insertions(+), 5 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 3b3423a4b..de9a6e7ad 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -365,30 +365,47 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message case 1: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES; ml_armed = true; + break; case 2: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; ml_armed = true; + break; case 3: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY; ml_armed = true; + break; case 4: ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION; ml_armed = true; + break; default: break; } - offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX; - offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX; - offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX; - offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX; + if (m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES || m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) { + + offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX; + offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX; + offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX; + offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX; + + } else if (m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY || m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) { + + /*Temporary hack to use set_quad_swarm_roll_pitch_yaw_thrust msg for position or velocity */ + /* Converts INT16 centimeters to float meters */ + offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / 100.0f; + offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / 100.0f; + offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / 100.0f; + offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / 100.0f; + + } if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) { ml_armed = false; @@ -420,7 +437,7 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message loc_pos_sp.x = offboard_control_sp.p1; loc_pos_sp.y = offboard_control_sp.p2; loc_pos_sp.yaw = offboard_control_sp.p3; - loc_pos_sp.z = offboard_control_sp.p4; + loc_pos_sp.z = -offboard_control_sp.p4; /* Close fds to allow position controller to use attitude controller */ if (_att_sp_pub > 0) { -- cgit v1.2.3 From 2951962c2104a0b2a284a7c5208171b257ed9734 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 12 Jun 2014 13:11:45 +0200 Subject: dataman: rename SYSTEM_STATE section to MISSION_STATE --- src/modules/dataman/dataman.c | 6 +++--- src/modules/dataman/dataman.h | 4 ++-- src/modules/mavlink/mavlink_main.cpp | 18 +++++++++--------- src/modules/navigator/navigator_main.cpp | 2 +- 4 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/modules/dataman/dataman.c b/src/modules/dataman/dataman.c index 14fee7c9a..4a89c7d41 100644 --- a/src/modules/dataman/dataman.c +++ b/src/modules/dataman/dataman.c @@ -116,7 +116,7 @@ static const unsigned g_per_item_max_index[DM_KEY_NUM_KEYS] = { DM_KEY_WAYPOINTS_OFFBOARD_0_MAX, DM_KEY_WAYPOINTS_OFFBOARD_1_MAX, DM_KEY_WAYPOINTS_ONBOARD_MAX, - DM_KEY_SYSTEM_STATE_MAX + DM_KEY_MISSION_STATE_MAX }; /* Table of offset for index 0 of each item type */ @@ -642,11 +642,11 @@ task_main(int argc, char *argv[]) for (unsigned i = 0; i < dm_number_of_funcs; i++) g_func_counts[i] = 0; - /* Initialize the item type locks, for now only DM_KEY_SYSTEM_STATE supports locking */ + /* Initialize the item type locks, for now only DM_KEY_MISSION_STATE supports locking */ sem_init(&g_sys_state_mutex, 1, 1); /* Initially unlocked */ for (unsigned i = 0; i < DM_KEY_NUM_KEYS; i++) g_item_locks[i] = NULL; - g_item_locks[DM_KEY_SYSTEM_STATE] = &g_sys_state_mutex; + g_item_locks[DM_KEY_MISSION_STATE] = &g_sys_state_mutex; g_task_should_exit = false; diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h index b25a2a5ef..215ec4c76 100644 --- a/src/modules/dataman/dataman.h +++ b/src/modules/dataman/dataman.h @@ -53,7 +53,7 @@ extern "C" { DM_KEY_WAYPOINTS_OFFBOARD_0, /* Mission way point coordinates sent over mavlink */ DM_KEY_WAYPOINTS_OFFBOARD_1, /* (alernate between 0 and 1) */ DM_KEY_WAYPOINTS_ONBOARD, /* Mission way point coordinates generated onboard */ - DM_KEY_SYSTEM_STATE, /* Persistent system state storage */ + DM_KEY_MISSION_STATE, /* Persistent mission state */ DM_KEY_NUM_KEYS /* Total number of item types defined */ } dm_item_t; @@ -64,7 +64,7 @@ extern "C" { DM_KEY_WAYPOINTS_OFFBOARD_0_MAX = NUM_MISSIONS_SUPPORTED, DM_KEY_WAYPOINTS_OFFBOARD_1_MAX = NUM_MISSIONS_SUPPORTED, DM_KEY_WAYPOINTS_ONBOARD_MAX = NUM_MISSIONS_SUPPORTED, - DM_KEY_SYSTEM_STATE_MAX = 1 + DM_KEY_MISSION_STATE_MAX = 1 }; /** Data persistence levels */ diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 9159f5d61..be1fc50a6 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -969,7 +969,7 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) state->action_timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; state->retry_timeout = MAVLINK_WPM_RETRY_TIMEOUT_DEFAULT; - int sys_state_size = dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state)); + int sys_state_size = dm_read(DM_KEY_MISSION_STATE, 0, &sys_state, sizeof(sys_state)); if (sys_state_size == sizeof(sys_state)) { if ((sys_state.offboard_waypoint_id >= 0) && (sys_state.offboard_waypoint_id <= 1)) { state->dataman_id = sys_state.offboard_waypoint_id; @@ -990,11 +990,11 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) state->size = seq; } else { - if (_verbose) { warnx("WPM init: invalid dataman ID %d stored in SYSTEM_STATE", sys_state.offboard_waypoint_id); } + if (_verbose) { warnx("WPM init: invalid dataman ID %d stored in MISSION_STATE", sys_state.offboard_waypoint_id); } } } else { - if (_verbose) { warnx("WPM init: dataman SYSTEM_STATE item has wrong size (%i, should be %u), ignoring", sys_state_size, sizeof(sys_state)); } + if (_verbose) { warnx("WPM init: dataman MISSION_STATE item has wrong size (%i, should be %u), ignoring", sys_state_size, sizeof(sys_state)); } } /* init mission topic */ @@ -1467,25 +1467,25 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) bool dm_result; /* since we are doing a read-modify-write we must lock the item type */ - dm_lock(DM_KEY_SYSTEM_STATE); + dm_lock(DM_KEY_MISSION_STATE); /* first read in the current state data, there may eventually be data other than the offboard index * and we must preserve it */ - ssize_t dm_state_size = dm_read(DM_KEY_SYSTEM_STATE, 0, &state, sizeof(state)); + ssize_t dm_state_size = dm_read(DM_KEY_MISSION_STATE, 0, &state, sizeof(state)); if (dm_state_size != sizeof(state)) { - warnx("dataman SYSTEM_STATE size invalid: %d, should be %d", dm_state_size, sizeof(state)); + warnx("dataman MISSION_STATE size invalid: %d, should be %d", dm_state_size, sizeof(state)); } /* set new dataman storage ID */ state.offboard_waypoint_id = _wpm->current_dataman_id; /* write back to dataman */ - dm_result = dm_write(DM_KEY_SYSTEM_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) != sizeof(state); + dm_result = dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) != sizeof(state); - dm_unlock(DM_KEY_SYSTEM_STATE); + dm_unlock(DM_KEY_MISSION_STATE); if (dm_result) { - if (_verbose) { warnx("WPM: MISSION_ITEM ERROR unable to write storage ID = %d to dataman SYSTEM_STATE", state.offboard_waypoint_id); } + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR unable to write storage ID = %d to dataman MISSION_STATE", state.offboard_waypoint_id); } mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD"); diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index a3426e65e..c7b39ba93 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -605,7 +605,7 @@ Navigator::task_main() /* Get the last offboard mission id */ persistent_system_state_t sys_state; - if (dm_read(DM_KEY_SYSTEM_STATE, 0, &sys_state, sizeof(sys_state)) == sizeof(sys_state)) { + if (dm_read(DM_KEY_MISSION_STATE, 0, &sys_state, sizeof(sys_state)) == sizeof(sys_state)) { if ((sys_state.offboard_waypoint_id >= 0) && (sys_state.offboard_waypoint_id <= 1)) _mission.set_offboard_dataman_id(sys_state.offboard_waypoint_id); } -- cgit v1.2.3 From b6b3ad6e1e31503d230ad6e7bc8f2d7b5b596ad7 Mon Sep 17 00:00:00 2001 From: Kynos Date: Fri, 13 Jun 2014 14:05:47 +0200 Subject: U-blox driver rework,, step 4 Config phase and parser rewrite --- src/drivers/gps/gps.cpp | 41 ++- src/drivers/gps/ubx.cpp | 903 ++++++++++++++++++++++++++---------------------- src/drivers/gps/ubx.h | 662 ++++++++++++++++++----------------- 3 files changed, 849 insertions(+), 757 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index f4d2f4b44..6ae325297 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -80,6 +80,14 @@ #endif static const int ERROR = -1; +/* class for dynamic allocation of satellite info data */ +class GPS_Sat_Info +{ +public: + struct satellite_info_s _data; +}; + + class GPS : public device::CDev { public: @@ -103,17 +111,17 @@ private: char _port[20]; ///< device / serial port path volatile int _task; //< worker task bool _healthy; ///< flag to signal if the GPS is ok - bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed + bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed bool _mode_changed; ///< flag that the GPS mode has changed gps_driver_mode_t _mode; ///< current mode GPS_Helper *_Helper; ///< instance of GPS parser - struct vehicle_gps_position_s _report_gps_pos; ///< uORB topic for gps position + GPS_Sat_Info *_Sat_Info; ///< instance of GPS sat info data object + struct vehicle_gps_position_s _report_gps_pos; ///< uORB topic for gps position orb_advert_t _report_gps_pos_pub; ///< uORB pub for gps position - struct satellite_info_s _report_sat_info; ///< uORB topic for satellite info + struct satellite_info_s *_p_report_sat_info; ///< pointer to uORB topic for satellite info orb_advert_t _report_sat_info_pub; ///< uORB pub for satellite info float _rate; ///< position update rate bool _fake_gps; ///< fake gps output - bool _enable_sat_info; ///< enable sat info /** @@ -165,11 +173,12 @@ GPS::GPS(const char *uart_path, bool fake_gps, bool enable_sat_info) : _mode_changed(false), _mode(GPS_DRIVER_MODE_UBX), _Helper(nullptr), + _Sat_Info(nullptr), _report_gps_pos_pub(-1), + _p_report_sat_info(nullptr), _report_sat_info_pub(-1), _rate(0.0f), - _fake_gps(fake_gps), - _enable_sat_info(enable_sat_info) + _fake_gps(fake_gps) { /* store port name */ strncpy(_port, uart_path, sizeof(_port)); @@ -179,7 +188,13 @@ GPS::GPS(const char *uart_path, bool fake_gps, bool enable_sat_info) : /* we need this potentially before it could be set in task_main */ g_dev = this; memset(&_report_gps_pos, 0, sizeof(_report_gps_pos)); - memset(&_report_sat_info, 0, sizeof(_report_sat_info)); + + /* create satellite info data object if requested */ + if (enable_sat_info) { + _Sat_Info = new(GPS_Sat_Info); + _p_report_sat_info = &_Sat_Info->_data; + memset(_p_report_sat_info, 0, sizeof(*_p_report_sat_info)); + } _debug_enabled = true; } @@ -214,7 +229,7 @@ GPS::init() /* start the GPS driver worker task */ _task = task_spawn_cmd("gps", SCHED_DEFAULT, - SCHED_PRIORITY_SLOW_DRIVER, 2000, (main_t)&GPS::task_main_trampoline, nullptr); + SCHED_PRIORITY_SLOW_DRIVER, 1500, (main_t)&GPS::task_main_trampoline, nullptr); if (_task < 0) { warnx("task start failed: %d", errno); @@ -320,7 +335,7 @@ GPS::task_main() switch (_mode) { case GPS_DRIVER_MODE_UBX: - _Helper = new UBX(_serial_fd, &_report_gps_pos, &_report_sat_info, _enable_sat_info); + _Helper = new UBX(_serial_fd, &_report_gps_pos, _p_report_sat_info); break; case GPS_DRIVER_MODE_MTK: @@ -353,12 +368,12 @@ GPS::task_main() _report_gps_pos_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report_gps_pos); } } - if (helper_ret & 2) { + if (_p_report_sat_info && (helper_ret & 2)) { if (_report_sat_info_pub > 0) { - orb_publish(ORB_ID(satellite_info), _report_sat_info_pub, &_report_sat_info); + orb_publish(ORB_ID(satellite_info), _report_sat_info_pub, _p_report_sat_info); } else { - _report_sat_info_pub = orb_advertise(ORB_ID(satellite_info), &_report_sat_info); + _report_sat_info_pub = orb_advertise(ORB_ID(satellite_info), _p_report_sat_info); } } } @@ -466,7 +481,7 @@ GPS::print_info() } warnx("port: %s, baudrate: %d, status: %s", _port, _baudrate, (_healthy) ? "OK" : "NOT OK"); - warnx("sat info: %s", (_enable_sat_info) ? "enabled" : "disabled"); + warnx("sat info: %s", (_p_report_sat_info != nullptr) ? "enabled" : "disabled"); if (_report_gps_pos.timestamp_position != 0) { warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report_gps_pos.fix_type, diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index 0708e23b4..1783ae0f7 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -34,14 +34,18 @@ /** * @file ubx.cpp * - * U-Blox protocol implementation. Following u-blox 6/7 Receiver Description + * U-Blox protocol implementation. Following u-blox 6/7/8 Receiver Description * including Prototol Specification. * * @author Thomas Gubler * @author Julian Oes * @author Anton Babushkin * + * @author Hannes Delago + * (rework, add ubx7+ compatibility) + * * @see http://www.u-blox.com/images/downloads/Product_Docs/u-blox6_ReceiverDescriptionProtocolSpec_%28GPS.G6-SW-10018%29.pdf + * @see http://www.u-blox.com/images/downloads/Product_Docs/u-bloxM8-V15_ReceiverDescriptionProtocolSpec_Public_%28UBX-13003221%29.pdf */ #include @@ -65,18 +69,28 @@ #define UBX_WAIT_BEFORE_READ 20 // ms, wait before reading to save read() calls #define DISABLE_MSG_INTERVAL 1000000 // us, try to disable message with this interval -#define MIN(X,Y) ((X) < (Y) ? (X) : (Y)) +#define MIN(X,Y) ((X) < (Y) ? (X) : (Y)) +#define SWAP16(X) ((((X) >> 8) & 0x00ff) | (((X) << 8) & 0xff00)) + +/**** Trace macros, disable for production builds */ +#define UBX_TRACE_PARSER(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* decoding progress in parse_char() */ +#define UBX_TRACE_RXMSG(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* Rx msgs in payload_rx_done() */ +#define UBX_TRACE_SVINFO(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* NAV-SVINFO processing (debug use only, will cause rx buffer overflows) */ + +/**** Warning macros, disable to save memory */ +#define UBX_WARN(s, ...) {warnx(s, ## __VA_ARGS__);} -UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info, const bool &enable_sat_info) : + +UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info) : _fd(fd), _gps_position(gps_position), _satellite_info(satellite_info), - _enable_sat_info(enable_sat_info), _configured(false), - _waiting_for_ack(false), + _ack_state(UBX_ACK_IDLE), _got_posllh(false), _got_velned(false), - _disable_cmd_last(0) + _disable_cmd_last(0), + _ack_waiting_msg(0) { decode_init(); } @@ -100,55 +114,41 @@ UBX::configure(unsigned &baudrate) /* flush input and wait for at least 20 ms silence */ decode_init(); - wait_for_ack(20); + receive(20); decode_init(); /* Send a CFG-PRT message to set the UBX protocol for in and out - * and leave the baudrate as it is, we just want an ACK-ACK from this - */ - type_gps_bin_cfg_prt_packet_t cfg_prt_packet; - /* Set everything else of the packet to 0, otherwise the module wont accept it */ - memset(&cfg_prt_packet, 0, sizeof(cfg_prt_packet)); - - _message_class_needed = UBX_CLASS_CFG; - _message_id_needed = UBX_MESSAGE_CFG_PRT; - - /* Define the package contents, don't change the baudrate */ - cfg_prt_packet.clsID = UBX_CLASS_CFG; - cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; - cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; - cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; - cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; - cfg_prt_packet.baudRate = baudrate; - cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; - cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; - - send_config_packet(_fd, (uint8_t *)&cfg_prt_packet, sizeof(cfg_prt_packet)); - - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { + * and leave the baudrate as it is, we just want an ACK-ACK for this */ + memset(&_buf.payload_tx_cfg_prt, 0, sizeof(_buf.payload_tx_cfg_prt)); + _buf.payload_tx_cfg_prt.portID = UBX_TX_CFG_PRT_PORTID; + _buf.payload_tx_cfg_prt.mode = UBX_TX_CFG_PRT_MODE; + _buf.payload_tx_cfg_prt.baudRate = baudrate; + _buf.payload_tx_cfg_prt.inProtoMask = UBX_TX_CFG_PRT_INPROTOMASK; + _buf.payload_tx_cfg_prt.outProtoMask = UBX_TX_CFG_PRT_OUTPROTOMASK; + + send_message(UBX_MSG_CFG_PRT, _buf.raw, sizeof(_buf.payload_tx_cfg_prt)); + + if (wait_for_ack(UBX_MSG_CFG_PRT, UBX_CONFIG_TIMEOUT, false) < 0) { /* try next baudrate */ continue; } /* Send a CFG-PRT message again, this time change the baudrate */ + memset(&_buf.payload_tx_cfg_prt, 0, sizeof(_buf.payload_tx_cfg_prt)); + _buf.payload_tx_cfg_prt.portID = UBX_TX_CFG_PRT_PORTID; + _buf.payload_tx_cfg_prt.mode = UBX_TX_CFG_PRT_MODE; + _buf.payload_tx_cfg_prt.baudRate = UBX_TX_CFG_PRT_BAUDRATE; + _buf.payload_tx_cfg_prt.inProtoMask = UBX_TX_CFG_PRT_INPROTOMASK; + _buf.payload_tx_cfg_prt.outProtoMask = UBX_TX_CFG_PRT_OUTPROTOMASK; - cfg_prt_packet.clsID = UBX_CLASS_CFG; - cfg_prt_packet.msgID = UBX_MESSAGE_CFG_PRT; - cfg_prt_packet.length = UBX_CFG_PRT_LENGTH; - cfg_prt_packet.portID = UBX_CFG_PRT_PAYLOAD_PORTID; - cfg_prt_packet.mode = UBX_CFG_PRT_PAYLOAD_MODE; - cfg_prt_packet.baudRate = UBX_CFG_PRT_PAYLOAD_BAUDRATE; - cfg_prt_packet.inProtoMask = UBX_CFG_PRT_PAYLOAD_INPROTOMASK; - cfg_prt_packet.outProtoMask = UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK; - - send_config_packet(_fd, (uint8_t *)&cfg_prt_packet, sizeof(cfg_prt_packet)); + send_message(UBX_MSG_CFG_PRT, _buf.raw, sizeof(_buf.payload_tx_cfg_prt)); /* no ACK is expected here, but read the buffer anyway in case we actually get an ACK */ - wait_for_ack(UBX_CONFIG_TIMEOUT); + wait_for_ack(UBX_MSG_CFG_PRT, UBX_CONFIG_TIMEOUT, false); - if (UBX_CFG_PRT_PAYLOAD_BAUDRATE != baudrate) { - set_baudrate(_fd, UBX_CFG_PRT_PAYLOAD_BAUDRATE); - baudrate = UBX_CFG_PRT_PAYLOAD_BAUDRATE; + if (UBX_TX_CFG_PRT_BAUDRATE != baudrate) { + set_baudrate(_fd, UBX_TX_CFG_PRT_BAUDRATE); + baudrate = UBX_TX_CFG_PRT_BAUDRATE; } /* at this point we have correct baudrate on both ends */ @@ -156,94 +156,68 @@ UBX::configure(unsigned &baudrate) } if (baud_i >= sizeof(baudrates) / sizeof(baudrates[0])) { - return 1; + return 1; // connection and/or baudrate detection failed } - /* send a CFG-RATE message to define update rate */ - type_gps_bin_cfg_rate_packet_t cfg_rate_packet; - memset(&cfg_rate_packet, 0, sizeof(cfg_rate_packet)); - - _message_class_needed = UBX_CLASS_CFG; - _message_id_needed = UBX_MESSAGE_CFG_RATE; + /* Send a CFG-RATE message to define update rate */ + memset(&_buf.payload_tx_cfg_rate, 0, sizeof(_buf.payload_tx_cfg_rate)); + _buf.payload_tx_cfg_rate.measRate = UBX_TX_CFG_RATE_MEASINTERVAL; + _buf.payload_tx_cfg_rate.navRate = UBX_TX_CFG_RATE_NAVRATE; + _buf.payload_tx_cfg_rate.timeRef = UBX_TX_CFG_RATE_TIMEREF; - cfg_rate_packet.clsID = UBX_CLASS_CFG; - cfg_rate_packet.msgID = UBX_MESSAGE_CFG_RATE; - cfg_rate_packet.length = UBX_CFG_RATE_LENGTH; - cfg_rate_packet.measRate = UBX_CFG_RATE_PAYLOAD_MEASINTERVAL; - cfg_rate_packet.navRate = UBX_CFG_RATE_PAYLOAD_NAVRATE; - cfg_rate_packet.timeRef = UBX_CFG_RATE_PAYLOAD_TIMEREF; + send_message(UBX_MSG_CFG_RATE, _buf.raw, sizeof(_buf.payload_tx_cfg_rate)); - send_config_packet(_fd, (uint8_t *)&cfg_rate_packet, sizeof(cfg_rate_packet)); - - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { - warnx("CFG FAIL: RATE"); + if (wait_for_ack(UBX_MSG_CFG_RATE, UBX_CONFIG_TIMEOUT, true) < 0) { return 1; } /* send a NAV5 message to set the options for the internal filter */ - type_gps_bin_cfg_nav5_packet_t cfg_nav5_packet; - memset(&cfg_nav5_packet, 0, sizeof(cfg_nav5_packet)); - - _message_class_needed = UBX_CLASS_CFG; - _message_id_needed = UBX_MESSAGE_CFG_NAV5; - - cfg_nav5_packet.clsID = UBX_CLASS_CFG; - cfg_nav5_packet.msgID = UBX_MESSAGE_CFG_NAV5; - cfg_nav5_packet.length = UBX_CFG_NAV5_LENGTH; - cfg_nav5_packet.mask = UBX_CFG_NAV5_PAYLOAD_MASK; - cfg_nav5_packet.dynModel = UBX_CFG_NAV5_PAYLOAD_DYNMODEL; - cfg_nav5_packet.fixMode = UBX_CFG_NAV5_PAYLOAD_FIXMODE; + memset(&_buf.payload_tx_cfg_nav5, 0, sizeof(_buf.payload_tx_cfg_nav5)); + _buf.payload_tx_cfg_nav5.mask = UBX_TX_CFG_NAV5_MASK; + _buf.payload_tx_cfg_nav5.dynModel = UBX_TX_CFG_NAV5_DYNMODEL; + _buf.payload_tx_cfg_nav5.fixMode = UBX_TX_CFG_NAV5_FIXMODE; - send_config_packet(_fd, (uint8_t *)&cfg_nav5_packet, sizeof(cfg_nav5_packet)); + send_message(UBX_MSG_CFG_NAV5, _buf.raw, sizeof(_buf.payload_tx_cfg_nav5)); - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { - warnx("CFG FAIL: NAV5"); + if (wait_for_ack(UBX_MSG_CFG_NAV5, UBX_CONFIG_TIMEOUT, true) < 0) { return 1; } /* configure message rates */ /* the last argument is divisor for measurement rate (set by CFG RATE), i.e. 1 means 5Hz */ - configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_POSLLH, 1); + configure_message_rate(UBX_MSG_NAV_POSLLH, 1); - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { - warnx("MSG CFG FAIL: NAV POSLLH"); + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { return 1; } - configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_TIMEUTC, 5); + configure_message_rate(UBX_MSG_NAV_TIMEUTC, 5); - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { - warnx("MSG CFG FAIL: NAV TIMEUTC"); + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { return 1; } - configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SOL, 1); + configure_message_rate(UBX_MSG_NAV_SOL, 1); - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { - warnx("MSG CFG FAIL: NAV SOL"); + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { return 1; } - configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_VELNED, 1); + configure_message_rate(UBX_MSG_NAV_VELNED, 1); - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { - warnx("MSG CFG FAIL: NAV VELNED"); + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { return 1; } - if (_enable_sat_info) { - configure_message_rate(UBX_CLASS_NAV, UBX_MESSAGE_NAV_SVINFO, 5); + configure_message_rate(UBX_MSG_NAV_SVINFO, (_satellite_info != nullptr) ? 5 : 0); - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { - warnx("MSG CFG FAIL: NAV SVINFO"); - return 1; - } + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { + return 1; } - configure_message_rate(UBX_CLASS_MON, UBX_MESSAGE_MON_HW, 1); + configure_message_rate(UBX_MSG_MON_HW, 1); - if (wait_for_ack(UBX_CONFIG_TIMEOUT) < 0) { - warnx("MSG CFG FAIL: MON HW"); + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { return 1; } @@ -251,27 +225,36 @@ UBX::configure(unsigned &baudrate) return 0; } -int -UBX::wait_for_ack(unsigned timeout) +int // -1 = NAK, error or timeout, 0 = ACK +UBX::wait_for_ack(const uint16_t msg, const unsigned timeout, const bool report) { - _waiting_for_ack = true; - uint64_t time_end = hrt_absolute_time() + timeout * 1000; + int ret = -1; - while ((timeout = (time_end - hrt_absolute_time()) / 1000) > 0) { - if (receive(timeout) > 0) { - if (!_waiting_for_ack) { - return 1; - } + _ack_state = UBX_ACK_WAITING; + _ack_waiting_msg = msg; // memorize sent msg class&ID for ACK check + + hrt_abstime time_started = hrt_absolute_time(); + + while ((_ack_state == UBX_ACK_WAITING) && (hrt_absolute_time() < time_started + timeout * 1000)) { + receive(timeout); + } + + if (_ack_state == UBX_ACK_GOT_ACK) { + ret = 0; // ACK received ok + } else if (report) { + if (_ack_state == UBX_ACK_GOT_NAK) { + UBX_WARN("ubx msg 0x%04x NAK", SWAP16((unsigned)msg)); } else { - return -1; // timeout or error receiving, or NAK + UBX_WARN("ubx msg 0x%04x ACK timeout", SWAP16((unsigned)msg)); } } - return -1; // timeout + _ack_state = UBX_ACK_IDLE; + return ret; } -int -UBX::receive(unsigned timeout) +int // -1 = error, 0 = no message handled, 1 = message handled, 2 = sat info message handled +UBX::receive(const unsigned timeout) { /* poll descriptor */ pollfd fds[1]; @@ -295,7 +278,7 @@ UBX::receive(unsigned timeout) if (ret < 0) { /* something went wrong when polling */ - warnx("poll error"); + UBX_WARN("ubx poll() err"); return -1; } else if (ret == 0) { @@ -323,433 +306,517 @@ UBX::receive(unsigned timeout) /* pass received bytes to the packet decoder */ for (int i = 0; i < count; i++) { - if (parse_char(buf[i]) > 0) { - handled |= handle_message(); - } + handled |= parse_char(buf[i]); } } } /* abort after timeout if no useful packets received */ if (time_started + timeout * 1000 < hrt_absolute_time()) { - warnx("timeout - no useful messages"); return -1; } } } -int -UBX::parse_char(uint8_t b) +int // 0 = decoding, 1 = message handled, 2 = sat info message handled +UBX::parse_char(const uint8_t b) { + int ret = 0; + switch (_decode_state) { - /* First, look for sync1 */ - case UBX_DECODE_UNINIT: - if (b == UBX_SYNC1) { - _decode_state = UBX_DECODE_GOT_SYNC1; - //### printf("\nA"); - } + /* Expecting Sync1 */ + case UBX_DECODE_SYNC1: + if (b == UBX_SYNC1) { // Sync1 found --> expecting Sync2 + UBX_TRACE_PARSER("\nA"); + _decode_state = UBX_DECODE_SYNC2; + } break; - /* Second, look for sync2 */ - case UBX_DECODE_GOT_SYNC1: - if (b == UBX_SYNC2) { - _decode_state = UBX_DECODE_GOT_SYNC2; - //### printf("B"); + /* Expecting Sync2 */ + case UBX_DECODE_SYNC2: + if (b == UBX_SYNC2) { // Sync2 found --> expecting Class + UBX_TRACE_PARSER("B"); + _decode_state = UBX_DECODE_CLASS; - } else { - /* Second start symbol was wrong, reset state machine */ + } else { // Sync1 not followed by Sync2: reset parser decode_init(); - /* don't return error, it can be just false sync1 */ - //### printf("-"); } + break; + /* Expecting Class */ + case UBX_DECODE_CLASS: + UBX_TRACE_PARSER("C"); + add_byte_to_checksum(b); // checksum is calculated for everything except Sync and Checksum bytes + _rx_msg = b; + _decode_state = UBX_DECODE_ID; break; - /* Now look for class */ - case UBX_DECODE_GOT_SYNC2: - /* everything except sync1 and sync2 needs to be added to the checksum */ + /* Expecting ID */ + case UBX_DECODE_ID: + UBX_TRACE_PARSER("D"); add_byte_to_checksum(b); - _message_class = b; - _decode_state = UBX_DECODE_GOT_CLASS; - //### printf("C"); + _rx_msg |= b << 8; + _decode_state = UBX_DECODE_LENGTH1; break; - case UBX_DECODE_GOT_CLASS: + /* Expecting first length byte */ + case UBX_DECODE_LENGTH1: + UBX_TRACE_PARSER("E"); add_byte_to_checksum(b); - _message_id = b; - _decode_state = UBX_DECODE_GOT_MESSAGEID; - //### printf("D"); + _rx_payload_length = b; + _decode_state = UBX_DECODE_LENGTH2; break; - case UBX_DECODE_GOT_MESSAGEID: + /* Expecting second length byte */ + case UBX_DECODE_LENGTH2: + UBX_TRACE_PARSER("F"); add_byte_to_checksum(b); - _payload_size = b; //this is the first length byte - _decode_state = UBX_DECODE_GOT_LENGTH1; - //### printf("E"); + _rx_payload_length |= b << 8; // calculate payload size + if (payload_rx_init() != 0) { // start payload reception + // payload will not be handled, discard message + decode_init(); + } else { + _decode_state = (_rx_payload_length > 0) ? UBX_DECODE_PAYLOAD : UBX_DECODE_CHKSUM1; + } break; - case UBX_DECODE_GOT_LENGTH1: + /* Expecting payload */ + case UBX_DECODE_PAYLOAD: + UBX_TRACE_PARSER("."); add_byte_to_checksum(b); - _payload_size += b << 8; // here comes the second byte of length - _decode_state = UBX_DECODE_GOT_LENGTH2; - //### printf("F"); + if (_rx_msg != UBX_MSG_NAV_SVINFO) { + ret = payload_rx_add(b); // add a payload byte + } else { + ret = payload_rx_add_svinfo(b); // add a svinfo payload byte + } + if (ret < 0) { + // payload not handled, discard message + decode_init(); + } else if (ret > 0) { + // payload complete, expecting checksum + _decode_state = UBX_DECODE_CHKSUM1; + } else { + // expecting more payload, stay in state UBX_DECODE_PAYLOAD + } + ret = 0; + break; + + /* Expecting first checksum byte */ + case UBX_DECODE_CHKSUM1: + if (_rx_ck_a != b) { + UBX_WARN("ubx checksum err"); + decode_init(); + } else { + _decode_state = UBX_DECODE_CHKSUM2; + } + break; + + /* Expecting second checksum byte */ + case UBX_DECODE_CHKSUM2: + if (_rx_ck_b != b) { + UBX_WARN("ubx checksum err"); + } else { + ret = payload_rx_done(); // finish payload processing + } + decode_init(); break; - case UBX_DECODE_GOT_LENGTH2: + default: + break; + } - /* Add to checksum if not yet at checksum byte */ - if (_rx_count < _payload_size) - add_byte_to_checksum(b); + return ret; +} - _rx_buffer[_rx_count] = b; +/** + * Start payload rx + */ +int // -1 = abort, 0 = continue +UBX::payload_rx_init() +{ + int ret = 0; - /* once the payload has arrived, we can process the information */ - if (_rx_count >= _payload_size + 1) { //+1 because of 2 checksum bytes - /* compare checksum */ - if (_rx_ck_a == _rx_buffer[_rx_count - 1] && _rx_ck_b == _rx_buffer[_rx_count]) { - //### printf("O\n"); - return 1; // message received successfully + _rx_state = UBX_RXMSG_HANDLE; // handle by default - } else { - warnx("checksum wrong"); - decode_init(); - return -1; - } + switch (_rx_msg) { + case UBX_MSG_NAV_POSLLH: + if (_rx_payload_length != sizeof(ubx_payload_rx_nav_posllh_t)) + _rx_state = UBX_RXMSG_ERROR_LENGTH; + else if (!_configured) + _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + break; - } else if (_rx_count < RECV_BUFFER_SIZE) { - _rx_count++; - //### printf("."); + case UBX_MSG_NAV_SOL: + if (_rx_payload_length != sizeof(ubx_payload_rx_nav_sol_t)) + _rx_state = UBX_RXMSG_ERROR_LENGTH; + else if (!_configured) + _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + break; - } else { - warnx("ubx: buffer full 0x%02x-0x%02x L%u", (unsigned)_message_class, (unsigned)_message_id, _payload_size); - decode_init(); - return -1; - } + case UBX_MSG_NAV_TIMEUTC: + if (_rx_payload_length != sizeof(ubx_payload_rx_nav_timeutc_t)) + _rx_state = UBX_RXMSG_ERROR_LENGTH; + else if (!_configured) + _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + break; + case UBX_MSG_NAV_SVINFO: + if (_satellite_info == nullptr) + _rx_state = UBX_RXMSG_DISABLE; // disable if sat info not requested + else if (!_configured) + _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + else + memset(_satellite_info, 0, sizeof(*_satellite_info)); // initialize sat info + break; + + case UBX_MSG_NAV_VELNED: + if (_rx_payload_length != sizeof(ubx_payload_rx_nav_velned_t)) + _rx_state = UBX_RXMSG_ERROR_LENGTH; + else if (!_configured) + _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + break; + + case UBX_MSG_MON_HW: + if ( (_rx_payload_length != sizeof(ubx_payload_rx_mon_hw_ubx6_t)) /* u-blox 6 msg format */ + && (_rx_payload_length != sizeof(ubx_payload_rx_mon_hw_ubx7_t))) /* u-blox 7+ msg format */ + _rx_state = UBX_RXMSG_ERROR_LENGTH; + else if (!_configured) + _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + break; + + case UBX_MSG_ACK_ACK: + if (_rx_payload_length != sizeof(ubx_payload_rx_ack_ack_t)) + _rx_state = UBX_RXMSG_ERROR_LENGTH; + else if (_configured) + _rx_state = UBX_RXMSG_IGNORE; // ignore if _configured + break; + + case UBX_MSG_ACK_NAK: + if (_rx_payload_length != sizeof(ubx_payload_rx_ack_nak_t)) + _rx_state = UBX_RXMSG_ERROR_LENGTH; + else if (_configured) + _rx_state = UBX_RXMSG_IGNORE; // ignore if _configured break; default: + _rx_state = UBX_RXMSG_DISABLE; // disable all other messages break; } - return 0; // message decoding in progress + switch (_rx_state) { + case UBX_RXMSG_HANDLE: // handle message + case UBX_RXMSG_IGNORE: // ignore message but don't report error + ret = 0; + break; + + case UBX_RXMSG_DISABLE: // disable unexpected messages + UBX_WARN("ubx msg 0x%04x len %u unexpected", SWAP16((unsigned)_rx_msg), (unsigned)_rx_payload_length); + + { + hrt_abstime t = hrt_absolute_time(); + + if (t > _disable_cmd_last + DISABLE_MSG_INTERVAL) { + /* don't attempt for every message to disable, some might not be disabled */ + _disable_cmd_last = t; + UBX_WARN("ubx disabling msg 0x%04x", SWAP16((unsigned)_rx_msg)); + configure_message_rate(_rx_msg, 0); + } + } + + ret = -1; // return error, abort handling this message + break; + + case UBX_RXMSG_ERROR_LENGTH: // error: invalid length + UBX_WARN("ubx msg 0x%04x invalid len %u", SWAP16((unsigned)_rx_msg), (unsigned)_rx_payload_length); + ret = -1; // return error, abort handling this message + break; + + default: // invalid message state + UBX_WARN("ubx internal err1"); + ret = -1; // return error, abort handling this message + break; + } + + return ret; } +/** + * Add payload rx byte + */ +int // -1 = error, 0 = ok, 1 = payload completed +UBX::payload_rx_add(const uint8_t b) +{ + int ret = 0; + + _buf.raw[_rx_payload_index] = b; + if (++_rx_payload_index >= _rx_payload_length) { + ret = 1; // payload received completely + } -int -UBX::handle_message() + return ret; +} + +/** + * Add svinfo payload rx byte + */ +int // -1 = error, 0 = ok, 1 = payload completed +UBX::payload_rx_add_svinfo(const uint8_t b) { int ret = 0; - if (_configured) { - /* handle only info messages when configured */ - switch (_message_class) { - case UBX_CLASS_NAV: - switch (_message_id) { - case UBX_MESSAGE_NAV_POSLLH: { - // printf("GOT NAV_POSLLH\n"); - gps_bin_nav_posllh_packet_t *packet = (gps_bin_nav_posllh_packet_t *) _rx_buffer; - - _gps_position->lat = packet->lat; - _gps_position->lon = packet->lon; - _gps_position->alt = packet->height_msl; - _gps_position->eph_m = (float)packet->hAcc * 1e-3f; // from mm to m - _gps_position->epv_m = (float)packet->vAcc * 1e-3f; // from mm to m - _gps_position->timestamp_position = hrt_absolute_time(); - - _rate_count_lat_lon++; - - _got_posllh = true; - ret = 1; - break; - } + if (_rx_payload_index < sizeof(ubx_payload_rx_nav_svinfo_part1_t)) { + // Fill Part 1 buffer + _buf.raw[_rx_payload_index] = b; + } else { + if (_rx_payload_index == sizeof(ubx_payload_rx_nav_svinfo_part1_t)) { + // Part 1 complete: decode Part 1 buffer + _satellite_info->count = MIN(_buf.payload_rx_nav_svinfo_part1.numCh, SAT_INFO_MAX_SATELLITES); + UBX_TRACE_SVINFO("SVINFO len %u numCh %u\n", (unsigned)_rx_payload_length, (unsigned)_buf.payload_rx_nav_svinfo_part1.numCh); + } + if (_rx_payload_index < sizeof(ubx_payload_rx_nav_svinfo_part1_t) + _satellite_info->count * sizeof(ubx_payload_rx_nav_svinfo_part2_t)) { + // Still room in _satellite_info: fill Part 2 buffer + unsigned buf_index = (_rx_payload_index - sizeof(ubx_payload_rx_nav_svinfo_part1_t)) % sizeof(ubx_payload_rx_nav_svinfo_part2_t); + _buf.raw[buf_index] = b; + if (buf_index == sizeof(ubx_payload_rx_nav_svinfo_part2_t) - 1) { + // Part 2 complete: decode Part 2 buffer + unsigned sat_index = (_rx_payload_index - sizeof(ubx_payload_rx_nav_svinfo_part1_t)) / sizeof(ubx_payload_rx_nav_svinfo_part2_t); + _satellite_info->used[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.flags & 0x01); + _satellite_info->snr[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.cno); + _satellite_info->elevation[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.elev); + _satellite_info->azimuth[sat_index] = (uint8_t)((float)_buf.payload_rx_nav_svinfo_part2.azim * 255.0f / 360.0f); + _satellite_info->svid[sat_index] = (uint8_t)(_buf.payload_rx_nav_svinfo_part2.svid); + UBX_TRACE_SVINFO("SVINFO #%02u used %u snr %3u elevation %3u azimuth %3u svid %3u\n", + (unsigned)sat_index + 1, + (unsigned)_satellite_info->used[sat_index], + (unsigned)_satellite_info->snr[sat_index], + (unsigned)_satellite_info->elevation[sat_index], + (unsigned)_satellite_info->azimuth[sat_index], + (unsigned)_satellite_info->svid[sat_index] + ); + } + } + } - case UBX_MESSAGE_NAV_SOL: { - // printf("GOT NAV_SOL\n"); - gps_bin_nav_sol_packet_t *packet = (gps_bin_nav_sol_packet_t *) _rx_buffer; + if (++_rx_payload_index >= _rx_payload_length) { + ret = 1; // payload received completely + } - _gps_position->fix_type = packet->gpsFix; - _gps_position->s_variance_m_s = packet->sAcc; - _gps_position->p_variance_m = packet->pAcc; - _gps_position->timestamp_variance = hrt_absolute_time(); - _gps_position->satellites_used = packet->numSV; + return ret; +} - ret = 1; - break; - } +/** + * Finish payload rx + */ +int // 0 = no message handled, 1 = message handled, 2 = sat info message handled +UBX::payload_rx_done(void) +{ + int ret = 0; + + // return if no message handled + if (_rx_state != UBX_RXMSG_HANDLE) { + return ret; + } + + // handle message + switch (_rx_msg) { + + case UBX_MSG_NAV_POSLLH: + UBX_TRACE_RXMSG("Rx NAV-POSLLH\n"); + + _gps_position->lat = _buf.payload_rx_nav_posllh.lat; + _gps_position->lon = _buf.payload_rx_nav_posllh.lon; + _gps_position->alt = _buf.payload_rx_nav_posllh.hMSL; + _gps_position->eph_m = (float)_buf.payload_rx_nav_posllh.hAcc * 1e-3f; // from mm to m + _gps_position->epv_m = (float)_buf.payload_rx_nav_posllh.vAcc * 1e-3f; // from mm to m + + _gps_position->timestamp_position = hrt_absolute_time(); + + _rate_count_lat_lon++; + _got_posllh = true; + + ret = 1; + break; + + case UBX_MSG_NAV_SOL: + UBX_TRACE_RXMSG("Rx NAV-SOL\n"); + + _gps_position->fix_type = _buf.payload_rx_nav_sol.gpsFix; + _gps_position->s_variance_m_s = _buf.payload_rx_nav_sol.sAcc; + _gps_position->p_variance_m = _buf.payload_rx_nav_sol.pAcc; + _gps_position->satellites_used = _buf.payload_rx_nav_sol.numSV; + + _gps_position->timestamp_variance = hrt_absolute_time(); + + ret = 1; + break; - case UBX_MESSAGE_NAV_TIMEUTC: { - // printf("GOT NAV_TIMEUTC\n"); - gps_bin_nav_timeutc_packet_t *packet = (gps_bin_nav_timeutc_packet_t *) _rx_buffer; + case UBX_MSG_NAV_TIMEUTC: + UBX_TRACE_RXMSG("Rx NAV-TIMEUTC\n"); - /* convert to unix timestamp */ - struct tm timeinfo; - timeinfo.tm_year = packet->year - 1900; - timeinfo.tm_mon = packet->month - 1; - timeinfo.tm_mday = packet->day; - timeinfo.tm_hour = packet->hour; - timeinfo.tm_min = packet->min; - timeinfo.tm_sec = packet->sec; - time_t epoch = mktime(&timeinfo); + { + /* convert to unix timestamp */ + struct tm timeinfo; + timeinfo.tm_year = _buf.payload_rx_nav_timeutc.year - 1900; + timeinfo.tm_mon = _buf.payload_rx_nav_timeutc.month - 1; + timeinfo.tm_mday = _buf.payload_rx_nav_timeutc.day; + timeinfo.tm_hour = _buf.payload_rx_nav_timeutc.hour; + timeinfo.tm_min = _buf.payload_rx_nav_timeutc.min; + timeinfo.tm_sec = _buf.payload_rx_nav_timeutc.sec; + time_t epoch = mktime(&timeinfo); #ifndef CONFIG_RTC - //Since we lack a hardware RTC, set the system time clock based on GPS UTC - //TODO generalize this by moving into gps.cpp? - timespec ts; - ts.tv_sec = epoch; - ts.tv_nsec = packet->time_nanoseconds; - clock_settime(CLOCK_REALTIME, &ts); + //Since we lack a hardware RTC, set the system time clock based on GPS UTC + //TODO generalize this by moving into gps.cpp? + timespec ts; + ts.tv_sec = epoch; + ts.tv_nsec = _buf.payload_rx_nav_timeutc.nano; + clock_settime(CLOCK_REALTIME, &ts); #endif - _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this - _gps_position->time_gps_usec += (uint64_t)(packet->time_nanoseconds * 1e-3f); - _gps_position->timestamp_time = hrt_absolute_time(); + _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this + _gps_position->time_gps_usec += (uint64_t)(_buf.payload_rx_nav_timeutc.nano * 1e-3f); + } - ret = 1; - break; - } + _gps_position->timestamp_time = hrt_absolute_time(); - case UBX_MESSAGE_NAV_SVINFO: { - //printf("GOT NAV_SVINFO\n"); - if (!_enable_sat_info) { // if satellite info processing not enabled: - break; // ignore and disable NAV-SVINFO message - } - const int length_part1 = 8; - gps_bin_nav_svinfo_part1_packet_t *packet_part1 = (gps_bin_nav_svinfo_part1_packet_t *) _rx_buffer; - const int length_part2 = 12; - gps_bin_nav_svinfo_part2_packet_t *packet_part2; - - //printf("Number of Channels: %d\n", packet_part1->numCh); - for (_satellite_info->count = 0; - _satellite_info->count < MIN(packet_part1->numCh, sizeof(_satellite_info->snr) / sizeof(_satellite_info->snr[0])); - _satellite_info->count++) { - /* set pointer to satellite_i information */ - packet_part2 = (gps_bin_nav_svinfo_part2_packet_t *) & (_rx_buffer[length_part1 + _satellite_info->count* length_part2]); - - /* write satellite information to global storage */ - _satellite_info->used[_satellite_info->count] = packet_part2->flags & 0x01; - _satellite_info->snr[_satellite_info->count] = packet_part2->cno; - _satellite_info->elevation[_satellite_info->count] = (uint8_t)(packet_part2->elev); - _satellite_info->azimuth[_satellite_info->count] = (uint8_t)((float)packet_part2->azim * 255.0f / 360.0f); - _satellite_info->svid[_satellite_info->count] = packet_part2->svid; - //printf("SAT %d: %d %d %d %d\n", _satellite_info->count, (int)sv_used, (int)packet_part2->cno, (int)(uint8_t)(packet_part2->elev), (int)packet_part2->svid); - } - - _satellite_info->timestamp = hrt_absolute_time(); - - ret = 2; - break; - } + ret = 1; + break; - case UBX_MESSAGE_NAV_VELNED: { - // printf("GOT NAV_VELNED\n"); - gps_bin_nav_velned_packet_t *packet = (gps_bin_nav_velned_packet_t *) _rx_buffer; + case UBX_MSG_NAV_SVINFO: + UBX_TRACE_RXMSG("Rx NAV-SVINFO\n"); - _gps_position->vel_m_s = (float)packet->speed * 1e-2f; - _gps_position->vel_n_m_s = (float)packet->velN * 1e-2f; /* NED NORTH velocity */ - _gps_position->vel_e_m_s = (float)packet->velE * 1e-2f; /* NED EAST velocity */ - _gps_position->vel_d_m_s = (float)packet->velD * 1e-2f; /* NED DOWN velocity */ - _gps_position->cog_rad = (float)packet->heading * M_DEG_TO_RAD_F * 1e-5f; - _gps_position->c_variance_rad = (float)packet->cAcc * M_DEG_TO_RAD_F * 1e-5f; - _gps_position->vel_ned_valid = true; - _gps_position->timestamp_velocity = hrt_absolute_time(); + // _satellite_info already populated by payload_rx_add_svinfo(), just add a timestamp + _satellite_info->timestamp = hrt_absolute_time(); - _rate_count_vel++; + ret = 2; + break; - _got_velned = true; - ret = 1; - break; - } + case UBX_MSG_NAV_VELNED: + UBX_TRACE_RXMSG("Rx NAV-VELNED\n"); - default: - break; - } + _gps_position->vel_m_s = (float)_buf.payload_rx_nav_velned.speed * 1e-2f; + _gps_position->vel_n_m_s = (float)_buf.payload_rx_nav_velned.velN * 1e-2f; /* NED NORTH velocity */ + _gps_position->vel_e_m_s = (float)_buf.payload_rx_nav_velned.velE * 1e-2f; /* NED EAST velocity */ + _gps_position->vel_d_m_s = (float)_buf.payload_rx_nav_velned.velD * 1e-2f; /* NED DOWN velocity */ + _gps_position->cog_rad = (float)_buf.payload_rx_nav_velned.heading * M_DEG_TO_RAD_F * 1e-5f; + _gps_position->c_variance_rad = (float)_buf.payload_rx_nav_velned.cAcc * M_DEG_TO_RAD_F * 1e-5f; + _gps_position->vel_ned_valid = true; - break; + _gps_position->timestamp_velocity = hrt_absolute_time(); - case UBX_CLASS_ACK: { - /* ignore ACK when already configured */ - ret = 1; - break; - } + _rate_count_vel++; + _got_velned = true; - case UBX_CLASS_MON: - switch (_message_id) { + ret = 1; + break; - case UBX_MESSAGE_MON_HW: - switch (_payload_size) { + case UBX_MSG_MON_HW: + UBX_TRACE_RXMSG("Rx MON-HW\n"); - case UBX_MON_HW_UBX6_RX_PAYLOAD_SIZE: /* u-blox 6 msg format */ - _gps_position->noise_per_ms = ((struct gps_bin_mon_hw_ubx6_packet*) _rx_buffer)->noisePerMS; - _gps_position->jamming_indicator = ((struct gps_bin_mon_hw_ubx6_packet*) _rx_buffer)->jamInd; - ret = 1; - break; + switch (_rx_payload_length) { - case UBX_MON_HW_UBX7_RX_PAYLOAD_SIZE: /* u-blox 7+ msg format */ - _gps_position->noise_per_ms = ((struct gps_bin_mon_hw_ubx7_packet*) _rx_buffer)->noisePerMS; - _gps_position->jamming_indicator = ((struct gps_bin_mon_hw_ubx7_packet*) _rx_buffer)->jamInd; - ret = 1; - break; + case sizeof(ubx_payload_rx_mon_hw_ubx6_t): /* u-blox 6 msg format */ + _gps_position->noise_per_ms = _buf.payload_rx_mon_hw_ubx6.noisePerMS; + _gps_position->jamming_indicator = _buf.payload_rx_mon_hw_ubx6.jamInd; - default: // unexpected payload size: - ret = 1; // ignore but don't disable msg - break; - } - break; + ret = 1; + break; - default: - break; - } + case sizeof(ubx_payload_rx_mon_hw_ubx7_t): /* u-blox 7+ msg format */ + _gps_position->noise_per_ms = _buf.payload_rx_mon_hw_ubx7.noisePerMS; + _gps_position->jamming_indicator = _buf.payload_rx_mon_hw_ubx7.jamInd; + + ret = 1; break; - default: + default: // unexpected payload size: + ret = 0; // don't handle message break; } + break; - if (ret == 0) { - /* message not handled */ - warnx("ubx: message not handled: 0x%02x-0x%02x L%u", (unsigned)_message_class, (unsigned)_message_id, _payload_size); - - hrt_abstime t = hrt_absolute_time(); + case UBX_MSG_ACK_ACK: + UBX_TRACE_RXMSG("Rx ACK-ACK\n"); - if (t > _disable_cmd_last + DISABLE_MSG_INTERVAL) { - /* don't attempt for every message to disable, some might not be disabled */ - _disable_cmd_last = t; - warnx("ubx: disabling message 0x%02x-0x%02x", (unsigned)_message_class, (unsigned)_message_id); - configure_message_rate(_message_class, _message_id, 0); - } + if ((_ack_state == UBX_ACK_WAITING) && (_buf.payload_rx_ack_ack.msg == _ack_waiting_msg)) { + _ack_state = UBX_ACK_GOT_ACK; } - } else { - /* handle only ACK while configuring */ - if (_message_class == UBX_CLASS_ACK) { - switch (_message_id) { - case UBX_MESSAGE_ACK_ACK: { - // printf("GOT ACK_ACK\n"); - gps_bin_ack_ack_packet_t *packet = (gps_bin_ack_ack_packet_t *) _rx_buffer; - - if (_waiting_for_ack) { - if (packet->clsID == _message_class_needed && packet->msgID == _message_id_needed) { - _waiting_for_ack = false; - ret = 1; - } - } - - break; - } + ret = 1; + break; - case UBX_MESSAGE_ACK_NAK: { - // printf("GOT ACK_NAK\n"); - warnx("ubx: not acknowledged"); - /* configuration obviously not successful */ - _waiting_for_ack = false; - break; - } + case UBX_MSG_ACK_NAK: + UBX_TRACE_RXMSG("Rx ACK-NAK\n"); - default: - break; - } + if ((_ack_state == UBX_ACK_WAITING) && (_buf.payload_rx_ack_ack.msg == _ack_waiting_msg)) { + _ack_state = UBX_ACK_GOT_NAK; } + + ret = 1; + break; + + default: + break; } - decode_init(); return ret; } void UBX::decode_init(void) { + _decode_state = UBX_DECODE_SYNC1; _rx_ck_a = 0; _rx_ck_b = 0; - _rx_count = 0; - _decode_state = UBX_DECODE_UNINIT; - _payload_size = 0; - /* don't reset _message_class, _message_id, _rx_buffer leave it for message handler */ + _rx_payload_length = 0; + _rx_payload_index = 0; } void -UBX::add_byte_to_checksum(uint8_t b) +UBX::add_byte_to_checksum(const uint8_t b) { _rx_ck_a = _rx_ck_a + b; _rx_ck_b = _rx_ck_b + _rx_ck_a; } void -UBX::add_checksum_to_message(uint8_t *message, const unsigned length) +UBX::calc_checksum(const uint8_t *buffer, const uint16_t length, ubx_checksum_t *checksum) { - uint8_t ck_a = 0; - uint8_t ck_b = 0; - unsigned i; - - for (i = 0; i < length - 2; i++) { - ck_a = ck_a + message[i]; - ck_b = ck_b + ck_a; + for (uint16_t i = 0; i < length; i++) { + checksum->ck_a = checksum->ck_a + buffer[i]; + checksum->ck_b = checksum->ck_b + checksum->ck_a; } - - /* the checksum is written to the last to bytes of a message */ - message[length - 2] = ck_a; - message[length - 1] = ck_b; } void -UBX::add_checksum(uint8_t *message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b) +UBX::configure_message_rate(const uint16_t msg, const uint8_t rate) { - for (unsigned i = 0; i < length; i++) { - ck_a = ck_a + message[i]; - ck_b = ck_b + ck_a; - } -} + ubx_payload_tx_cfg_msg_t cfg_msg; // don't use _buf (allow interleaved operation) -void -UBX::configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate) -{ - struct ubx_cfg_msg_rate msg; - msg.msg_class = msg_class; - msg.msg_id = msg_id; - msg.rate = rate; - send_message(UBX_CLASS_CFG, UBX_MESSAGE_CFG_MSG, &msg, sizeof(msg)); + cfg_msg.msg = msg; + cfg_msg.rate = rate; + + send_message(UBX_MSG_CFG_MSG, (uint8_t *)&cfg_msg, sizeof(cfg_msg)); } void -UBX::send_config_packet(const int &fd, uint8_t *packet, const unsigned length) +UBX::send_message(const uint16_t msg, const uint8_t *payload, const uint16_t length) { - ssize_t ret = 0; + ubx_header_t header = {UBX_SYNC1, UBX_SYNC2}; + ubx_checksum_t checksum = {0, 0}; - /* calculate the checksum now */ - add_checksum_to_message(packet, length); + // Populate header + header.msg = msg; + header.length = length; - const uint8_t sync_bytes[] = {UBX_SYNC1, UBX_SYNC2}; + // Calculate checksum + calc_checksum(((uint8_t*)&header) + 2, sizeof(header) - 2, &checksum); // skip 2 sync bytes + calc_checksum(payload, length, &checksum); - /* start with the two sync bytes */ - ret += write(fd, sync_bytes, sizeof(sync_bytes)); - ret += write(fd, packet, length); - - if (ret != (int)length + (int)sizeof(sync_bytes)) // XXX is there a neater way to get rid of the unsigned signed warning? - warnx("ubx: configuration write fail"); -} - -void -UBX::send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size) -{ - struct ubx_header header; - uint8_t ck_a = 0, ck_b = 0; - header.sync1 = UBX_SYNC1; - header.sync2 = UBX_SYNC2; - header.msg_class = msg_class; - header.msg_id = msg_id; - header.length = size; - - add_checksum((uint8_t *)&header.msg_class, sizeof(header) - 2, ck_a, ck_b); - add_checksum((uint8_t *)msg, size, ck_a, ck_b); - - /* configure ACK check */ - _message_class_needed = msg_class; - _message_id_needed = msg_id; - - write(_fd, (const char *)&header, sizeof(header)); - write(_fd, (const char *)msg, size); - write(_fd, (const char *)&ck_a, 1); - write(_fd, (const char *)&ck_b, 1); + // Send message + write(_fd, (const void *)&header, sizeof(header)); + write(_fd, (const void *)payload, length); + write(_fd, (const void *)&checksum, sizeof(checksum)); } diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index 50df3ada2..f084fc655 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2012, 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -41,6 +41,9 @@ * @author Julian Oes * @author Anton Babushkin * + * @author Hannes Delago + * (rework, add ubx7+ compatibility) + * */ #ifndef UBX_H_ @@ -48,346 +51,341 @@ #include "gps_helper.h" -#define UBX_ENABLE_NAV_SVINFO 1 /* TODO: make this a command line option, allocate buffer(s) dynamically */ - #define UBX_SYNC1 0xB5 #define UBX_SYNC2 0x62 -/* ClassIDs (the ones that are used) */ -#define UBX_CLASS_NAV 0x01 -//#define UBX_CLASS_RXM 0x02 -#define UBX_CLASS_ACK 0x05 -#define UBX_CLASS_CFG 0x06 -#define UBX_CLASS_MON 0x0A - -/* MessageIDs (the ones that are used) */ -#define UBX_MESSAGE_NAV_POSLLH 0x02 -#define UBX_MESSAGE_NAV_SOL 0x06 -#define UBX_MESSAGE_NAV_VELNED 0x12 -#define UBX_MESSAGE_NAV_TIMEUTC 0x21 -#define UBX_MESSAGE_NAV_SVINFO 0x30 -#define UBX_MESSAGE_ACK_NAK 0x00 -#define UBX_MESSAGE_ACK_ACK 0x01 -#define UBX_MESSAGE_CFG_PRT 0x00 -#define UBX_MESSAGE_CFG_MSG 0x01 -#define UBX_MESSAGE_CFG_RATE 0x08 -#define UBX_MESSAGE_CFG_NAV5 0x24 -#define UBX_MESSAGE_MON_HW 0x09 - -/* Rx msg payload sizes */ -#define UBX_NAV_POSLLH_RX_PAYLOAD_SIZE 28 /**< NAV_POSLLH Rx msg payload size */ -#define UBX_NAV_SOL_RX_PAYLOAD_SIZE 52 /**< NAV_SOL Rx msg payload size */ -#define UBX_NAV_VELNED_RX_PAYLOAD_SIZE 36 /**< NAV_VELNED Rx msg payload size */ -#define UBX_NAV_TIMEUTC_RX_PAYLOAD_SIZE 20 /**< NAV_TIMEUTC Rx msg payload size */ -#define UBX_MON_HW_UBX6_RX_PAYLOAD_SIZE 68 /**< MON_HW Rx msg payload size for u-blox 6 and below */ -#define UBX_MON_HW_UBX7_RX_PAYLOAD_SIZE 60 /**< MON_HW Rx msg payload size for u-blox 7 and above */ -#define UBX_MAX_RX_PAYLOAD_SIZE 70 /**< arbitrary maximum for calculating parser buffer size w/o NAV_SVINFO active */ +/* Message Classes */ +#define UBX_CLASS_NAV 0x01 +#define UBX_CLASS_ACK 0x05 +#define UBX_CLASS_CFG 0x06 +#define UBX_CLASS_MON 0x0A + +/* Message IDs */ +#define UBX_ID_NAV_POSLLH 0x02 +#define UBX_ID_NAV_SOL 0x06 +#define UBX_ID_NAV_VELNED 0x12 +#define UBX_ID_NAV_TIMEUTC 0x21 +#define UBX_ID_NAV_SVINFO 0x30 +#define UBX_ID_ACK_NAK 0x00 +#define UBX_ID_ACK_ACK 0x01 +#define UBX_ID_CFG_PRT 0x00 +#define UBX_ID_CFG_MSG 0x01 +#define UBX_ID_CFG_RATE 0x08 +#define UBX_ID_CFG_NAV5 0x24 +#define UBX_ID_MON_HW 0x09 + +/* Message Classes & IDs */ +#define UBX_MSG_NAV_POSLLH ((UBX_CLASS_NAV) | UBX_ID_NAV_POSLLH << 8) +#define UBX_MSG_NAV_SOL ((UBX_CLASS_NAV) | UBX_ID_NAV_SOL << 8) +#define UBX_MSG_NAV_VELNED ((UBX_CLASS_NAV) | UBX_ID_NAV_VELNED << 8) +#define UBX_MSG_NAV_TIMEUTC ((UBX_CLASS_NAV) | UBX_ID_NAV_TIMEUTC << 8) +#define UBX_MSG_NAV_SVINFO ((UBX_CLASS_NAV) | UBX_ID_NAV_SVINFO << 8) +#define UBX_MSG_ACK_NAK ((UBX_CLASS_ACK) | UBX_ID_ACK_NAK << 8) +#define UBX_MSG_ACK_ACK ((UBX_CLASS_ACK) | UBX_ID_ACK_ACK << 8) +#define UBX_MSG_CFG_PRT ((UBX_CLASS_CFG) | UBX_ID_CFG_PRT << 8) +#define UBX_MSG_CFG_MSG ((UBX_CLASS_CFG) | UBX_ID_CFG_MSG << 8) +#define UBX_MSG_CFG_RATE ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8) +#define UBX_MSG_CFG_NAV5 ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8) +#define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8) /* NAV_SVINFO has variable length w/o a published max size, so limit processing to UBX_MAX_NUM_SAT */ -#define UBX_MAX_NUM_SAT 50 /**< Practical observed max number of satellites in SVNFO msg */ -#define UBX_NAV_SVINFO_RX_PAYLOAD_SIZE (8 + 12 * UBX_MAX_NUM_SAT) /**< NAV_SVINFO Rx msg payload size */ - -/* CFG class Tx msg defs */ -#define UBX_CFG_PRT_LENGTH 20 -#define UBX_CFG_PRT_PAYLOAD_PORTID 0x01 /**< UART1 */ -#define UBX_CFG_PRT_PAYLOAD_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ -#define UBX_CFG_PRT_PAYLOAD_BAUDRATE 38400 /**< choose 38400 as GPS baudrate */ -#define UBX_CFG_PRT_PAYLOAD_INPROTOMASK 0x01 /**< UBX in */ -#define UBX_CFG_PRT_PAYLOAD_OUTPROTOMASK 0x01 /**< UBX out */ - -#define UBX_CFG_RATE_LENGTH 6 -#define UBX_CFG_RATE_PAYLOAD_MEASINTERVAL 200 /**< 200ms for 5Hz */ -#define UBX_CFG_RATE_PAYLOAD_NAVRATE 1 /**< cannot be changed */ -#define UBX_CFG_RATE_PAYLOAD_TIMEREF 0 /**< 0: UTC, 1: GPS time */ - -#define UBX_CFG_NAV5_LENGTH 36 -#define UBX_CFG_NAV5_PAYLOAD_MASK 0x0005 /**< XXX only update dynamic model and fix mode */ -#define UBX_CFG_NAV5_PAYLOAD_DYNMODEL 7 /**< 0: portable, 2: stationary, 3: pedestrian, 4: automotive, 5: sea, 6: airborne <1g, 7: airborne <2g, 8: airborne <4g */ -#define UBX_CFG_NAV5_PAYLOAD_FIXMODE 2 /**< 1: 2D only, 2: 3D only, 3: Auto 2D/3D */ - -#define UBX_CFG_MSG_LENGTH 8 -#define UBX_CFG_MSG_PAYLOAD_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ -#define UBX_CFG_MSG_PAYLOAD_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ -#define UBX_CFG_MSG_PAYLOAD_RATE1_05HZ 10 - - -// ************ -/** the structures of the binary packets */ -#pragma pack(push, 1) +#define UBX_MAX_NUM_SAT_SVINFO 50 /**< Practical observed max number of satellites in SVNFO msg */ +#define UBX_PAYLOAD_NAV_SVINFO (8 + 12 * UBX_MAX_NUM_SAT_SVINFO) /**< NAV_SVINFO Rx msg payload size */ -struct ubx_header { - uint8_t sync1; - uint8_t sync2; - uint8_t msg_class; - uint8_t msg_id; - uint16_t length; -}; +/* TX CFG-PRT message contents */ +#define UBX_TX_CFG_PRT_PORTID 0x01 /**< UART1 */ +#define UBX_TX_CFG_PRT_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ +#define UBX_TX_CFG_PRT_BAUDRATE 38400 /**< choose 38400 as GPS baudrate */ +#define UBX_TX_CFG_PRT_INPROTOMASK 0x01 /**< UBX in */ +#define UBX_TX_CFG_PRT_OUTPROTOMASK 0x01 /**< UBX out */ -typedef struct { - uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ - int32_t lon; /**< Longitude * 1e-7, deg */ - int32_t lat; /**< Latitude * 1e-7, deg */ - int32_t height; /**< Height above Ellipsoid, mm */ - int32_t height_msl; /**< Height above mean sea level, mm */ - uint32_t hAcc; /**< Horizontal Accuracy Estimate, mm */ - uint32_t vAcc; /**< Vertical Accuracy Estimate, mm */ - uint8_t ck_a; - uint8_t ck_b; -} gps_bin_nav_posllh_packet_t; +/* TX CFG-RATE message contents */ +#define UBX_TX_CFG_RATE_MEASINTERVAL 200 /**< 200ms for 5Hz */ +#define UBX_TX_CFG_RATE_NAVRATE 1 /**< cannot be changed */ +#define UBX_TX_CFG_RATE_TIMEREF 0 /**< 0: UTC, 1: GPS time */ -typedef struct { - uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ - int32_t time_nanoseconds; /**< Fractional Nanoseconds remainder of rounded ms above, range -500000 .. 500000 */ - int16_t week; /**< GPS week (GPS time) */ - uint8_t gpsFix; /**< GPS Fix: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */ - uint8_t flags; - int32_t ecefX; - int32_t ecefY; - int32_t ecefZ; - uint32_t pAcc; - int32_t ecefVX; - int32_t ecefVY; - int32_t ecefVZ; - uint32_t sAcc; - uint16_t pDOP; - uint8_t reserved1; - uint8_t numSV; /**< Number of SVs used in Nav Solution */ - uint32_t reserved2; - uint8_t ck_a; - uint8_t ck_b; -} gps_bin_nav_sol_packet_t; +/* TX CFG-NAV5 message contents */ +#define UBX_TX_CFG_NAV5_MASK 0x0005 /**< Only update dynamic model and fix mode */ +#define UBX_TX_CFG_NAV5_DYNMODEL 7 /**< 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g */ +#define UBX_TX_CFG_NAV5_FIXMODE 2 /**< 1 2D only, 2 3D only, 3 Auto 2D/3D */ -typedef struct { - uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ - uint32_t time_accuracy; /**< Time Accuracy Estimate, ns */ - int32_t time_nanoseconds; /**< Nanoseconds of second, range -1e9 .. 1e9 (UTC) */ - uint16_t year; /**< Year, range 1999..2099 (UTC) */ - uint8_t month; /**< Month, range 1..12 (UTC) */ - uint8_t day; /**< Day of Month, range 1..31 (UTC) */ - uint8_t hour; /**< Hour of Day, range 0..23 (UTC) */ - uint8_t min; /**< Minute of Hour, range 0..59 (UTC) */ - uint8_t sec; /**< Seconds of Minute, range 0..59 (UTC) */ - uint8_t valid_flag; /**< Validity Flags (see ubx documentation) */ - uint8_t ck_a; - uint8_t ck_b; -} gps_bin_nav_timeutc_packet_t; - -//typedef struct { -// uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ -// uint16_t gDOP; /**< Geometric DOP (scaling 0.01) */ -// uint16_t pDOP; /**< Position DOP (scaling 0.01) */ -// uint16_t tDOP; /**< Time DOP (scaling 0.01) */ -// uint16_t vDOP; /**< Vertical DOP (scaling 0.01) */ -// uint16_t hDOP; /**< Horizontal DOP (scaling 0.01) */ -// uint16_t nDOP; /**< Northing DOP (scaling 0.01) */ -// uint16_t eDOP; /**< Easting DOP (scaling 0.01) */ -// uint8_t ck_a; -// uint8_t ck_b; -//} gps_bin_nav_dop_packet_t; +/* TX CFG-MSG message contents */ +#define UBX_TX_CFG_MSG_RATE1_5HZ 0x01 /**< {0x00, 0x01, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ +#define UBX_TX_CFG_MSG_RATE1_1HZ 0x05 /**< {0x00, 0x05, 0x00, 0x00, 0x00, 0x00} the second entry is for UART1 */ +#define UBX_TX_CFG_MSG_RATE1_05HZ 10 -typedef struct { - uint32_t time_milliseconds; /**< GPS Millisecond Time of Week */ - uint8_t numCh; /**< Number of channels */ - uint8_t globalFlags; - uint16_t reserved2; -} gps_bin_nav_svinfo_part1_packet_t; +/*** u-blox protocol binary message and payload definitions ***/ +#pragma pack(push, 1) +/* General: Header */ typedef struct { - uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */ - uint8_t svid; /**< Satellite ID */ - uint8_t flags; - uint8_t quality; - uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength), dbHz */ - int8_t elev; /**< Elevation in integer degrees */ - int16_t azim; /**< Azimuth in integer degrees */ - int32_t prRes; /**< Pseudo range residual in centimetres */ - -} gps_bin_nav_svinfo_part2_packet_t; + uint8_t sync1; + uint8_t sync2; + uint16_t msg; + uint16_t length; +} ubx_header_t; +/* General: Checksum */ typedef struct { - uint8_t ck_a; - uint8_t ck_b; -} gps_bin_nav_svinfo_part3_packet_t; + uint8_t ck_a; + uint8_t ck_b; +} ubx_checksum_t ; +/* Rx NAV-POSLLH */ typedef struct { - uint32_t time_milliseconds; // GPS Millisecond Time of Week - int32_t velN; //NED north velocity, cm/s - int32_t velE; //NED east velocity, cm/s - int32_t velD; //NED down velocity, cm/s - uint32_t speed; //Speed (3-D), cm/s - uint32_t gSpeed; //Ground Speed (2-D), cm/s - int32_t heading; //Heading of motion 2-D, deg, scaling: 1e-5 - uint32_t sAcc; //Speed Accuracy Estimate, cm/s - uint32_t cAcc; //Course / Heading Accuracy Estimate, scaling: 1e-5 - uint8_t ck_a; - uint8_t ck_b; -} gps_bin_nav_velned_packet_t; - -struct gps_bin_mon_hw_ubx6_packet { - uint32_t pinSel; - uint32_t pinBank; - uint32_t pinDir; - uint32_t pinVal; - uint16_t noisePerMS; - uint16_t agcCnt; - uint8_t aStatus; - uint8_t aPower; - uint8_t flags; - uint8_t __reserved1; - uint32_t usedMask; - uint8_t VP[25]; - uint8_t jamInd; - uint16_t __reserved3; - uint32_t pinIrq; - uint32_t pulLH; - uint32_t pullL; -}; - -struct gps_bin_mon_hw_ubx7_packet { - uint32_t pinSel; - uint32_t pinBank; - uint32_t pinDir; - uint32_t pinVal; - uint16_t noisePerMS; - uint16_t agcCnt; - uint8_t aStatus; - uint8_t aPower; - uint8_t flags; - uint8_t __reserved1; - uint32_t usedMask; - uint8_t VP[17]; - uint8_t jamInd; - uint16_t __reserved3; - uint32_t pinIrq; - uint32_t pulLH; - uint32_t pullL; -}; - -//typedef struct { -// int32_t time_milliseconds; /**< Measurement integer millisecond GPS time of week */ -// int16_t week; /**< Measurement GPS week number */ -// uint8_t numVis; /**< Number of visible satellites */ -// -// //... rest of package is not used in this implementation -// -//} gps_bin_rxm_svsi_packet_t; - + uint32_t iTOW; /**< GPS Time of Week [ms] */ + int32_t lon; /**< Longitude [1e-7 deg] */ + int32_t lat; /**< Latitude [1e-7 deg] */ + int32_t height; /**< Height above ellipsoid [mm] */ + int32_t hMSL; /**< Height above mean sea level [mm] */ + uint32_t hAcc; /**< Horizontal accuracy estimate [mm] */ + uint32_t vAcc; /**< Vertical accuracy estimate [mm] */ +} ubx_payload_rx_nav_posllh_t; + +/* Rx NAV-SOL */ typedef struct { - uint8_t clsID; - uint8_t msgID; - uint8_t ck_a; - uint8_t ck_b; -} gps_bin_ack_ack_packet_t; - + uint32_t iTOW; /**< GPS Time of Week [ms] */ + int32_t fTOW; /**< Fractional part of iTOW (range: +/-500000) [ns] */ + int16_t week; /**< GPS week */ + uint8_t gpsFix; /**< GPSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GPS + dead reckoning, 5 = time only fix */ + uint8_t flags; + int32_t ecefX; + int32_t ecefY; + int32_t ecefZ; + uint32_t pAcc; + int32_t ecefVX; + int32_t ecefVY; + int32_t ecefVZ; + uint32_t sAcc; + uint16_t pDOP; + uint8_t reserved1; + uint8_t numSV; /**< Number of SVs used in Nav Solution */ + uint32_t reserved2; +} ubx_payload_rx_nav_sol_t; + +/* Rx NAV-TIMEUTC */ typedef struct { - uint8_t clsID; - uint8_t msgID; - uint8_t ck_a; - uint8_t ck_b; -} gps_bin_ack_nak_packet_t; - + uint32_t iTOW; /**< GPS Time of Week [ms] */ + uint32_t tAcc; /**< Time accuracy estimate (UTC) [ns] */ + int32_t nano; /**< Fraction of second, range -1e9 .. 1e9 (UTC) [ns] */ + uint16_t year; /**< Year, range 1999..2099 (UTC) */ + uint8_t month; /**< Month, range 1..12 (UTC) */ + uint8_t day; /**< Day of month, range 1..31 (UTC) */ + uint8_t hour; /**< Hour of day, range 0..23 (UTC) */ + uint8_t min; /**< Minute of hour, range 0..59 (UTC) */ + uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */ + uint8_t valid; /**< Validity Flags (see ubx documentation) */ +} ubx_payload_rx_nav_timeutc_t; + +/* Rx NAV-SVINFO Part 1 */ typedef struct { - uint8_t clsID; - uint8_t msgID; - uint16_t length; - uint8_t portID; - uint8_t res0; - uint16_t res1; - uint32_t mode; - uint32_t baudRate; - uint16_t inProtoMask; - uint16_t outProtoMask; - uint16_t flags; - uint16_t pad; - uint8_t ck_a; - uint8_t ck_b; -} type_gps_bin_cfg_prt_packet_t; + uint32_t iTOW; /**< GPS Time of Week [ms] */ + uint8_t numCh; /**< Number of channels */ + uint8_t globalFlags; + uint16_t reserved2; +} ubx_payload_rx_nav_svinfo_part1_t; +/* Rx NAV-SVINFO Part 2 (repeated) */ typedef struct { - uint8_t clsID; - uint8_t msgID; - uint16_t length; - uint16_t measRate; - uint16_t navRate; - uint16_t timeRef; - uint8_t ck_a; - uint8_t ck_b; -} type_gps_bin_cfg_rate_packet_t; - + uint8_t chn; /**< Channel number, 255 for SVs not assigned to a channel */ + uint8_t svid; /**< Satellite ID */ + uint8_t flags; + uint8_t quality; + uint8_t cno; /**< Carrier to Noise Ratio (Signal Strength) [dbHz] */ + int8_t elev; /**< Elevation [deg] */ + int16_t azim; /**< Azimuth [deg] */ + int32_t prRes; /**< Pseudo range residual [cm] */ +} ubx_payload_rx_nav_svinfo_part2_t; + +/* Rx NAV-VELNED */ typedef struct { - uint8_t clsID; - uint8_t msgID; - uint16_t length; - uint16_t mask; - uint8_t dynModel; - uint8_t fixMode; - int32_t fixedAlt; - uint32_t fixedAltVar; - int8_t minElev; - uint8_t drLimit; - uint16_t pDop; - uint16_t tDop; - uint16_t pAcc; - uint16_t tAcc; - uint8_t staticHoldThresh; - uint8_t dgpsTimeOut; - uint32_t reserved2; - uint32_t reserved3; - uint32_t reserved4; - uint8_t ck_a; - uint8_t ck_b; -} type_gps_bin_cfg_nav5_packet_t; - + uint32_t iTOW; /**< GPS Time of Week [ms] */ + int32_t velN; /**< North velocity component [cm/s]*/ + int32_t velE; /**< East velocity component [cm/s]*/ + int32_t velD; /**< Down velocity component [cm/s]*/ + uint32_t speed; /**< Speed (3-D) [cm/s] */ + uint32_t gSpeed; /**< Ground speed (2-D) [cm/s] */ + int32_t heading; /**< Heading of motion 2-D [1e-5 deg] */ + uint32_t sAcc; /**< Speed accuracy estimate [cm/s] */ + uint32_t cAcc; /**< Course / Heading accuracy estimate [1e-5 deg] */ +} ubx_payload_rx_nav_velned_t; + +/* Rx MON-HW (ubx6) */ typedef struct { - uint8_t clsID; - uint8_t msgID; - uint16_t length; - uint8_t msgClass_payload; - uint8_t msgID_payload; - uint8_t rate; - uint8_t ck_a; - uint8_t ck_b; -} type_gps_bin_cfg_msg_packet_t; + uint32_t pinSel; + uint32_t pinBank; + uint32_t pinDir; + uint32_t pinVal; + uint16_t noisePerMS; + uint16_t agcCnt; + uint8_t aStatus; + uint8_t aPower; + uint8_t flags; + uint8_t reserved1; + uint32_t usedMask; + uint8_t VP[25]; + uint8_t jamInd; + uint16_t reserved3; + uint32_t pinIrq; + uint32_t pullH; + uint32_t pullL; +} ubx_payload_rx_mon_hw_ubx6_t; + +/* Rx MON-HW (ubx7+) */ +typedef struct { + uint32_t pinSel; + uint32_t pinBank; + uint32_t pinDir; + uint32_t pinVal; + uint16_t noisePerMS; + uint16_t agcCnt; + uint8_t aStatus; + uint8_t aPower; + uint8_t flags; + uint8_t reserved1; + uint32_t usedMask; + uint8_t VP[17]; + uint8_t jamInd; + uint16_t reserved3; + uint32_t pinIrq; + uint32_t pullH; + uint32_t pullL; +} ubx_payload_rx_mon_hw_ubx7_t; + +/* Rx ACK-ACK */ +typedef union { + uint16_t msg; + struct { + uint8_t clsID; + uint8_t msgID; + }; +} ubx_payload_rx_ack_ack_t; + +/* Rx ACK-NAK */ +typedef union { + uint16_t msg; + struct { + uint8_t clsID; + uint8_t msgID; + }; +} ubx_payload_rx_ack_nak_t; + +/* Tx CFG-PRT */ +typedef struct { + uint8_t portID; + uint8_t reserved0; + uint16_t txReady; + uint32_t mode; + uint32_t baudRate; + uint16_t inProtoMask; + uint16_t outProtoMask; + uint16_t flags; + uint16_t reserved5; +} ubx_payload_tx_cfg_prt_t; + +/* Tx CFG-RATE */ +typedef struct { + uint16_t measRate; /**< Measurement Rate, GPS measurements are taken every measRate milliseconds */ + uint16_t navRate; /**< Navigation Rate, in number of measurement cycles. This parameter cannot be changed, and must be set to 1 */ + uint16_t timeRef; /**< Alignment to reference time: 0 = UTC time, 1 = GPS time */ +} ubx_payload_tx_cfg_rate_t; -struct ubx_cfg_msg_rate { - uint8_t msg_class; - uint8_t msg_id; +/* Tx CFG-NAV5 */ +typedef struct { + uint16_t mask; + uint8_t dynModel; /**< Dynamic Platform model: 0 Portable, 2 Stationary, 3 Pedestrian, 4 Automotive, 5 Sea, 6 Airborne <1g, 7 Airborne <2g, 8 Airborne <4g */ + uint8_t fixMode; /**< Position Fixing Mode: 1 2D only, 2 3D only, 3 Auto 2D/3D */ + int32_t fixedAlt; + uint32_t fixedAltVar; + int8_t minElev; + uint8_t drLimit; + uint16_t pDop; + uint16_t tDop; + uint16_t pAcc; + uint16_t tAcc; + uint8_t staticHoldThresh; + uint8_t dgpsTimeOut; + uint8_t cnoThreshNumSVs; /**< (ubx7+ only, else 0) */ + uint8_t cnoThresh; /**< (ubx7+ only, else 0) */ + uint16_t reserved; + uint16_t staticHoldMaxDist; /**< (ubx8+ only, else 0) */ + uint8_t utcStandard; /**< (ubx8+ only, else 0) */ + uint8_t reserved3; + uint32_t reserved4; +} ubx_payload_tx_cfg_nav5_t; + +/* Tx CFG-MSG */ +typedef struct { + union { + uint16_t msg; + struct { + uint8_t msgClass; + uint8_t msgID; + }; + }; uint8_t rate; -}; +} ubx_payload_tx_cfg_msg_t; + +/* General message and payload buffer union */ +typedef union { + ubx_payload_rx_nav_posllh_t payload_rx_nav_posllh; + ubx_payload_rx_nav_sol_t payload_rx_nav_sol; + ubx_payload_rx_nav_timeutc_t payload_rx_nav_timeutc; + ubx_payload_rx_nav_svinfo_part1_t payload_rx_nav_svinfo_part1; + ubx_payload_rx_nav_svinfo_part2_t payload_rx_nav_svinfo_part2; + ubx_payload_rx_nav_velned_t payload_rx_nav_velned; + ubx_payload_rx_mon_hw_ubx6_t payload_rx_mon_hw_ubx6; + ubx_payload_rx_mon_hw_ubx7_t payload_rx_mon_hw_ubx7; + ubx_payload_rx_ack_ack_t payload_rx_ack_ack; + ubx_payload_rx_ack_nak_t payload_rx_ack_nak; + ubx_payload_tx_cfg_prt_t payload_tx_cfg_prt; + ubx_payload_tx_cfg_rate_t payload_tx_cfg_rate; + ubx_payload_tx_cfg_nav5_t payload_tx_cfg_nav5; + ubx_payload_tx_cfg_msg_t payload_tx_cfg_msg; + uint8_t raw[]; +} ubx_buf_t; +#pragma pack(pop) +/*** END OF u-blox protocol binary message and payload definitions ***/ -// END the structures of the binary packets -// ************ - +/* Decoder state */ typedef enum { - UBX_DECODE_UNINIT = 0, - UBX_DECODE_GOT_SYNC1, - UBX_DECODE_GOT_SYNC2, - UBX_DECODE_GOT_CLASS, - UBX_DECODE_GOT_MESSAGEID, - UBX_DECODE_GOT_LENGTH1, - UBX_DECODE_GOT_LENGTH2 + UBX_DECODE_SYNC1 = 0, + UBX_DECODE_SYNC2, + UBX_DECODE_CLASS, + UBX_DECODE_ID, + UBX_DECODE_LENGTH1, + UBX_DECODE_LENGTH2, + UBX_DECODE_PAYLOAD, + UBX_DECODE_CHKSUM1, + UBX_DECODE_CHKSUM2 } ubx_decode_state_t; -//typedef type_gps_bin_ubx_state gps_bin_ubx_state_t; -#pragma pack(pop) +/* Rx message state */ +typedef enum { + UBX_RXMSG_IGNORE = 0, + UBX_RXMSG_HANDLE, + UBX_RXMSG_DISABLE, + UBX_RXMSG_ERROR_LENGTH +} ubx_rxmsg_state_t; + + +/* ACK state */ +typedef enum { + UBX_ACK_IDLE = 0, + UBX_ACK_WAITING, + UBX_ACK_GOT_ACK, + UBX_ACK_GOT_NAK +} ubx_ack_state_t; -/* calculate parser rx buffer size dependent on NAV_SVINFO enabled or not */ -/* TODO: make this a command line option, allocate buffer dynamically */ -#define RECV_BUFFER_OVERHEAD 10 // add this to the maximum Rx msg payload size to account for msg overhead */ -#if (UBX_ENABLE_NAV_SVINFO != 0) - #define RECV_BUFFER_SIZE (UBX_NAV_SVINFO_RX_PAYLOAD_SIZE + RECV_BUFFER_OVERHEAD) -#else - #define RECV_BUFFER_SIZE (UBX_MAX_RX_PAYLOAD_SIZE + RECV_BUFFER_OVERHEAD) -#endif class UBX : public GPS_Helper { public: - UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info, const bool &enable_sat_info); + UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct satellite_info_s *satellite_info); ~UBX(); - int receive(unsigned timeout); + int receive(const unsigned timeout); int configure(unsigned &baudrate); private: @@ -395,12 +393,23 @@ private: /** * Parse the binary UBX packet */ - int parse_char(uint8_t b); + int parse_char(const uint8_t b); + + /** + * Start payload rx + */ + int payload_rx_init(void); + + /** + * Add payload rx byte + */ + int payload_rx_add(const uint8_t b); + int payload_rx_add_svinfo(const uint8_t b); /** - * Handle the package once it has arrived + * Finish payload rx */ - int handle_message(void); + int payload_rx_done(void); /** * Reset the parse state machine for a fresh start @@ -410,45 +419,46 @@ private: /** * While parsing add every byte (except the sync bytes) to the checksum */ - void add_byte_to_checksum(uint8_t); + void add_byte_to_checksum(const uint8_t); /** - * Add the two checksum bytes to an outgoing message + * Send a message */ - void add_checksum_to_message(uint8_t *message, const unsigned length); + void send_message(const uint16_t msg, const uint8_t *payload, const uint16_t length); /** - * Helper to send a config packet + * Configure message rate */ - void send_config_packet(const int &fd, uint8_t *packet, const unsigned length); - - void configure_message_rate(uint8_t msg_class, uint8_t msg_id, uint8_t rate); + void configure_message_rate(const uint16_t msg, const uint8_t rate); - void send_message(uint8_t msg_class, uint8_t msg_id, void *msg, uint8_t size); - - void add_checksum(uint8_t *message, const unsigned length, uint8_t &ck_a, uint8_t &ck_b); + /** + * Calculate & add checksum for given buffer + */ + void calc_checksum(const uint8_t *buffer, const uint16_t length, ubx_checksum_t *checksum); - int wait_for_ack(unsigned timeout); + /** + * Wait for message acknowledge + */ + int wait_for_ack(const uint16_t msg, const unsigned timeout, const bool report); int _fd; struct vehicle_gps_position_s *_gps_position; struct satellite_info_s *_satellite_info; bool _enable_sat_info; bool _configured; - bool _waiting_for_ack; + ubx_ack_state_t _ack_state; bool _got_posllh; bool _got_velned; - uint8_t _message_class_needed; - uint8_t _message_id_needed; ubx_decode_state_t _decode_state; - uint8_t _rx_buffer[RECV_BUFFER_SIZE]; - unsigned _rx_count; + uint16_t _rx_msg; + ubx_rxmsg_state_t _rx_state; + uint16_t _rx_payload_length; + uint16_t _rx_payload_index; uint8_t _rx_ck_a; uint8_t _rx_ck_b; - uint8_t _message_class; - uint8_t _message_id; - unsigned _payload_size; hrt_abstime _disable_cmd_last; + uint16_t _ack_waiting_msg; + ubx_buf_t _buf; }; #endif /* UBX_H_ */ -- cgit v1.2.3 From 7724e3d889eecd6733c6e85341a9f0b97faa37cf Mon Sep 17 00:00:00 2001 From: Kynos Date: Fri, 13 Jun 2014 23:18:58 +0200 Subject: Remove unreferenced SVINFO length defines --- src/drivers/gps/ubx.h | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index f084fc655..8fd8d4da6 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -88,10 +88,6 @@ #define UBX_MSG_CFG_NAV5 ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8) #define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8) -/* NAV_SVINFO has variable length w/o a published max size, so limit processing to UBX_MAX_NUM_SAT */ -#define UBX_MAX_NUM_SAT_SVINFO 50 /**< Practical observed max number of satellites in SVNFO msg */ -#define UBX_PAYLOAD_NAV_SVINFO (8 + 12 * UBX_MAX_NUM_SAT_SVINFO) /**< NAV_SVINFO Rx msg payload size */ - /* TX CFG-PRT message contents */ #define UBX_TX_CFG_PRT_PORTID 0x01 /**< UART1 */ #define UBX_TX_CFG_PRT_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ -- cgit v1.2.3 From 91b590ef584cfc67be7555e3d7272bb94bc9b2b4 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 13 Jun 2014 23:40:48 +0200 Subject: Move MISSION_STATE read/write from mavlink to navigator and commander --- src/modules/commander/commander.cpp | 22 ++++-- src/modules/dataman/dataman.h | 12 +--- src/modules/mavlink/mavlink_main.cpp | 119 ++++++------------------------- src/modules/navigator/mission.cpp | 33 +++++++++ src/modules/navigator/mission.h | 5 ++ src/modules/navigator/navigator_main.cpp | 7 -- 6 files changed, 80 insertions(+), 118 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index e992706ac..d2f8c2994 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -76,6 +76,7 @@ #include #include #include +#include #include #include @@ -89,6 +90,7 @@ #include #include #include +#include #include "px4_custom_mode.h" #include "commander_helper.h" @@ -691,6 +693,11 @@ int commander_thread_main(int argc, char *argv[]) /* publish initial state */ status_pub = orb_advertise(ORB_ID(vehicle_status), &status); + if (status_pub < 0) { + warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n"); + warnx("exiting."); + exit(ERROR); + } /* armed topic */ orb_advert_t armed_pub; @@ -708,10 +715,17 @@ int commander_thread_main(int argc, char *argv[]) struct home_position_s home; memset(&home, 0, sizeof(home)); - if (status_pub < 0) { - warnx("ERROR: orb_advertise for topic vehicle_status failed (uorb app running?).\n"); - warnx("exiting."); - exit(ERROR); + /* init mission state */ + mission_s mission; + if (dm_read(DM_KEY_MISSION_STATE, 0, &mission, sizeof(mission_s)) == sizeof(mission_s)) { + if (mission.dataman_id >= 0 && mission.dataman_id <= 1) { + mavlink_log_info(mavlink_fd, "[cmd] dataman ID: %i, count: %u, current: %i", + mission.dataman_id, mission.count, mission.current_index); + orb_advert_t mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission); + close(mission_pub); + } else { + mavlink_log_info(mavlink_fd, "[cmd] reading mission state failed"); + } } mavlink_log_info(mavlink_fd, "[cmd] started"); diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h index 215ec4c76..dbace21ef 100644 --- a/src/modules/dataman/dataman.h +++ b/src/modules/dataman/dataman.h @@ -53,7 +53,7 @@ extern "C" { DM_KEY_WAYPOINTS_OFFBOARD_0, /* Mission way point coordinates sent over mavlink */ DM_KEY_WAYPOINTS_OFFBOARD_1, /* (alernate between 0 and 1) */ DM_KEY_WAYPOINTS_ONBOARD, /* Mission way point coordinates generated onboard */ - DM_KEY_MISSION_STATE, /* Persistent mission state */ + DM_KEY_MISSION_STATE, /* Persistent mission state */ DM_KEY_NUM_KEYS /* Total number of item types defined */ } dm_item_t; @@ -127,16 +127,6 @@ extern "C" { dm_reset_reason restart_type /* The last reset type */ ); - /* NOTE: The following structure defines the persistent system state data stored in the single - entry DM_KEY_SYSTEM_STATE_KEY item type. It contains global system state information that - needs to survive restarts. This definition is application specific so it doesn't really belong - in this header, but till I find it a better home here it is */ - - typedef struct { - char offboard_waypoint_id; /* the index of the active offboard waypoint data */ - /* (DM_KEY_WAYPOINTS_OFFBOARD_n) or -1 for none */ - } persistent_system_state_t; - #ifdef __cplusplus } #endif diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 5c6ef68ee..bc4376b84 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -18,7 +18,6 @@ * * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, @@ -964,8 +963,6 @@ int Mavlink::map_mission_item_to_mavlink_mission_item(const struct mission_item_ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) { - persistent_system_state_t sys_state; - /* init WPM state */ state->size = 0; state->max_size = MAVLINK_WPM_MAX_WP_COUNT; @@ -980,40 +977,7 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) state->action_timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; state->retry_timeout = MAVLINK_WPM_RETRY_TIMEOUT_DEFAULT; - int sys_state_size = dm_read(DM_KEY_MISSION_STATE, 0, &sys_state, sizeof(sys_state)); - if (sys_state_size == sizeof(sys_state)) { - if ((sys_state.offboard_waypoint_id >= 0) && (sys_state.offboard_waypoint_id <= 1)) { - state->dataman_id = sys_state.offboard_waypoint_id; - - if (_verbose) { warnx("WPM init: using dataman ID %d", state->dataman_id); } - - /* count waypoints in current waypoints storage */ - dm_item_t dm_id = _wpm->dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; - struct mission_item_s mission_item; - - int seq = 0; - while (seq < state->max_size && dm_read(dm_id, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { - seq++; - } - - if (_verbose) { warnx("WPM init: found %d items", seq); } - - state->size = seq; - - } else { - if (_verbose) { warnx("WPM init: invalid dataman ID %d stored in MISSION_STATE", sys_state.offboard_waypoint_id); } - } - - } else { - if (_verbose) { warnx("WPM init: dataman MISSION_STATE item has wrong size (%i, should be %u), ignoring", sys_state_size, sizeof(sys_state)); } - } - - /* init mission topic */ - mission.count = state->size; - mission.dataman_id = state->dataman_id; - mission.current_index = -1; // TODO store current index in dataman? - - publish_mission(); + } /* @@ -1081,10 +1045,10 @@ void Mavlink::mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uin void Mavlink::mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq) { - dm_item_t dm_id = _wpm->dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; + dm_item_t dm_item = _wpm->dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; struct mission_item_s mission_item; - if (dm_read(dm_id, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { + if (dm_read(dm_item, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { /* create mission_item_s from mavlink_mission_item_t */ mavlink_mission_item_t wp; @@ -1103,7 +1067,7 @@ void Mavlink::mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); mavlink_missionlib_send_gcs_string("#audio: Unable to read from micro SD"); - if (_verbose) { warnx("WPM: Send WAYPOINT ERROR: could not read seq %u from dataman ID %i", seq, dm_id); } + if (_verbose) { warnx("WPM: Send WAYPOINT ERROR: could not read seq %u from dataman ID %i", seq, _wpm->dataman_id); } } } @@ -1214,9 +1178,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) mission.current_index = wpc.seq; publish_mission(); - /* don't answer yet, wait for the navigator to respond, then publish the mission_result */ -// mavlink_wpm_send_waypoint_current(wpc.seq); - } else { if (_verbose) { warnx("WPM: MISSION_SET_CURRENT ERROR: not in list (%d)", wpc.seq); } @@ -1392,6 +1353,8 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) _wpm->current_count = wpc.count; _wpm->current_dataman_id = _wpm->dataman_id == 0 ? 1 : 0; // use inactive storage for transmission + mission.current_index = -1; + mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); } } @@ -1442,10 +1405,10 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) break; } - dm_item_t dm_id = _wpm->current_dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; + dm_item_t dm_item = _wpm->current_dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; - if (dm_write(dm_id, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, sizeof(struct mission_item_s)) != sizeof(struct mission_item_s)) { - if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, dm_id); } + if (dm_write(dm_item, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, sizeof(struct mission_item_s)) != sizeof(struct mission_item_s)) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _wpm->current_dataman_id); } mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD"); @@ -1453,6 +1416,11 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) break; } + /* waypoint marked as current */ + if (wp.current) { + mission.current_index = wp.seq; + } + if (_verbose) { warnx("WPM: MISSION_ITEM seq %u received", wp.seq); } _wpm->current_wp_id = wp.seq + 1; @@ -1463,65 +1431,23 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) _wpm->current_state = MAVLINK_WPM_STATE_IDLE; - /* write terminator item */ - if (_wpm->current_count < _wpm->max_size) { - if (dm_write(dm_id, _wpm->current_count, DM_PERSIST_POWER_ON_RESET, nullptr, 0) != 0) { - if (_verbose) { warnx("WPM: MISSION_ITEM ERROR writing terminator item"); } + mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); - break; - } - } + /* update WPM state */ + _wpm->dataman_id = _wpm->current_dataman_id; + _wpm->size = _wpm->current_count; - /* offboard mission data saved correctly, now update the persistent system state */ - persistent_system_state_t state; - bool dm_result; + /* update mission topic */ + mission.dataman_id = _wpm->dataman_id; + mission.count = _wpm->current_count; - /* since we are doing a read-modify-write we must lock the item type */ - dm_lock(DM_KEY_MISSION_STATE); - - /* first read in the current state data, there may eventually be data other than the offboard index - * and we must preserve it */ - ssize_t dm_state_size = dm_read(DM_KEY_MISSION_STATE, 0, &state, sizeof(state)); - if (dm_state_size != sizeof(state)) { - warnx("dataman MISSION_STATE size invalid: %d, should be %d", dm_state_size, sizeof(state)); - } - - /* set new dataman storage ID */ - state.offboard_waypoint_id = _wpm->current_dataman_id; - - /* write back to dataman */ - dm_result = dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &state, sizeof(state)) != sizeof(state); - - dm_unlock(DM_KEY_MISSION_STATE); - - if (dm_result) { - if (_verbose) { warnx("WPM: MISSION_ITEM ERROR unable to write storage ID = %d to dataman MISSION_STATE", state.offboard_waypoint_id); } - - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); - mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD"); - - } else { - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); - - /* update WPM state */ - _wpm->dataman_id = _wpm->current_dataman_id; - _wpm->size = _wpm->current_count; - - /* update mission topic */ - mission.dataman_id = _wpm->dataman_id; - mission.count = _wpm->current_count; - mission.current_index = 0; - - publish_mission(); - } + publish_mission(); } else { /* request next item */ mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); } } - break; } @@ -1545,6 +1471,7 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) _wpm->size = 0; /* update mission topic */ + mission.dataman_id = _wpm->dataman_id; mission.count = 0; mission.current_index = -1; diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 9244063b1..d9d8353f6 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -430,6 +430,37 @@ Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *missio return false; } +void +Mission::save_offboard_mission_state() +{ + mission_s mission_state; + + /* lock MISSION_STATE item */ + dm_lock(DM_KEY_MISSION_STATE); + + /* read current state */ + int read_res = dm_read(DM_KEY_MISSION_STATE, 0, &mission_state, sizeof(mission_s)); + + /* check if state actually changed to save flash write cycles */ + if (read_res != sizeof(mission_s) || mission_state.dataman_id != _offboard_mission.dataman_id || + mission_state.count != _offboard_mission.count || + mission_state.current_index != _current_offboard_mission_index) { + + mission_state.dataman_id = _offboard_mission.dataman_id; + mission_state.count = _offboard_mission.count; + mission_state.current_index = _current_offboard_mission_index; + + /* write modifyed state only if changed */ + if (dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission_state, sizeof(mission_s)) != sizeof(mission_s)) { + mavlink_log_critical(_navigator->get_mavlink_fd(), "error saving mission state"); + + } + } + + /* unlock MISSION_STATE item */ + dm_unlock(DM_KEY_MISSION_STATE); +} + void Mission::report_mission_item_reached() { @@ -445,6 +476,8 @@ Mission::report_current_offboard_mission_item() { _mission_result.index_current_mission = _current_offboard_mission_index; publish_mission_result(); + + save_offboard_mission_state(); } void diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index 322aaf96a..98b11bade 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -141,6 +141,11 @@ private: bool read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index, struct mission_item_s *new_mission_item); + /** + * Save current offboard mission state to dataman + */ + void save_offboard_mission_state(); + /** * Report that a mission item has been reached */ diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 888c8e7f4..a3c190c7f 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -227,13 +227,6 @@ Navigator::task_main() warnx("Could not clear geofence"); } - /* Get the last offboard mission id */ - persistent_system_state_t sys_state; - if (dm_read(DM_KEY_MISSION_STATE, 0, &sys_state, sizeof(sys_state)) == sizeof(sys_state)) { - if ((sys_state.offboard_waypoint_id >= 0) && (sys_state.offboard_waypoint_id <= 1)) - _mission.set_offboard_dataman_id(sys_state.offboard_waypoint_id); - } - /* do subscriptions */ _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position)); _capabilities_sub = orb_subscribe(ORB_ID(navigation_capabilities)); -- cgit v1.2.3 From ffd9ac7e081aebb3d6329a0f6c09812d1c0c4523 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 14 Jun 2014 01:31:23 +0200 Subject: mavlink: fix WPM initialization --- src/modules/mavlink/mavlink_main.cpp | 59 ++++++++++++++++++++---------------- src/modules/mavlink/mavlink_main.h | 4 ++- 2 files changed, 36 insertions(+), 27 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index bc4376b84..126c4dfc6 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -72,8 +72,6 @@ #include #include -#include -#include #include "mavlink_bridge_header.h" #include "mavlink_main.h" @@ -245,7 +243,7 @@ Mavlink::Mavlink() : _loop_perf(perf_alloc(PC_ELAPSED, "mavlink")) { _wpm = &_wpm_s; - mission.count = 0; + fops.ioctl = (int (*)(file *, int, long unsigned int))&mavlink_dev_ioctl; _instance_id = Mavlink::instance_count(); @@ -860,10 +858,10 @@ void Mavlink::publish_mission() { /* Initialize mission publication if necessary */ if (_mission_pub < 0) { - _mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission); + _mission_pub = orb_advertise(ORB_ID(offboard_mission), &_mission); } else { - orb_publish(ORB_ID(offboard_mission), _mission_pub, &mission); + orb_publish(ORB_ID(offboard_mission), _mission_pub, &_mission); } } @@ -963,10 +961,20 @@ int Mavlink::map_mission_item_to_mavlink_mission_item(const struct mission_item_ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) { + /* get offboard_mission topic */ + int mission_sub = orb_subscribe(ORB_ID(offboard_mission)); + if (orb_copy(ORB_ID(offboard_mission), mission_sub, &_mission)) { + /* error getting topic, init to safe values */ + _mission.dataman_id = 0; + _mission.count = 0; + _mission.current_index = -1; + } + close(mission_sub); + /* init WPM state */ - state->size = 0; + state->size = _mission.count; state->max_size = MAVLINK_WPM_MAX_WP_COUNT; - state->dataman_id = 0; + state->dataman_id = _mission.dataman_id; state->current_state = MAVLINK_WPM_STATE_IDLE; state->current_partner_sysid = 0; state->current_partner_compid = 0; @@ -977,7 +985,7 @@ void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) state->action_timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; state->retry_timeout = MAVLINK_WPM_RETRY_TIMEOUT_DEFAULT; - + warnx("wpm init: dataman_id=%d, count=%u, current=%d", state->dataman_id, state->size, _mission.current_index); } /* @@ -1035,7 +1043,7 @@ void Mavlink::mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uin wpc.target_system = sysid; wpc.target_component = compid; - wpc.count = mission.count; + wpc.count = _wpm->size; mavlink_msg_mission_count_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpc); mavlink_missionlib_send_message(&msg); @@ -1058,6 +1066,7 @@ void Mavlink::mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t wp.target_system = sysid; wp.target_component = compid; wp.seq = seq; + wp.current = (_mission_result.index_current_mission == seq) ? 1 : 0; mavlink_msg_mission_item_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wp); mavlink_missionlib_send_message(&msg); @@ -1175,7 +1184,7 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) if (wpc.seq < _wpm->size) { if (_verbose) { warnx("WPM: MISSION_SET_CURRENT OK (%d)", wpc.seq); } - mission.current_index = wpc.seq; + _mission.current_index = wpc.seq; publish_mission(); } else { @@ -1353,7 +1362,7 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) _wpm->current_count = wpc.count; _wpm->current_dataman_id = _wpm->dataman_id == 0 ? 1 : 0; // use inactive storage for transmission - mission.current_index = -1; + _mission.current_index = -1; mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); } @@ -1418,7 +1427,7 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) /* waypoint marked as current */ if (wp.current) { - mission.current_index = wp.seq; + _mission.current_index = wp.seq; } if (_verbose) { warnx("WPM: MISSION_ITEM seq %u received", wp.seq); } @@ -1438,8 +1447,8 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) _wpm->size = _wpm->current_count; /* update mission topic */ - mission.dataman_id = _wpm->dataman_id; - mission.count = _wpm->current_count; + _mission.dataman_id = _wpm->dataman_id; + _mission.count = _wpm->current_count; publish_mission(); @@ -1471,9 +1480,9 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) _wpm->size = 0; /* update mission topic */ - mission.dataman_id = _wpm->dataman_id; - mission.count = 0; - mission.current_index = -1; + _mission.dataman_id = _wpm->dataman_id; + _mission.count = 0; + _mission.current_index = -1; publish_mission(); @@ -1754,7 +1763,6 @@ Mavlink::pass_message(mavlink_message_t *msg) } - int Mavlink::task_main(int argc, char *argv[]) { @@ -1918,8 +1926,7 @@ Mavlink::task_main(int argc, char *argv[]) mavlink_wpm_init(_wpm); int mission_result_sub = orb_subscribe(ORB_ID(mission_result)); - struct mission_result_s mission_result; - memset(&mission_result, 0, sizeof(mission_result)); + memset(&_mission_result, 0, sizeof(_mission_result)); _task_running = true; @@ -2027,19 +2034,19 @@ Mavlink::task_main(int argc, char *argv[]) orb_check(mission_result_sub, &updated); if (updated) { - orb_copy(ORB_ID(mission_result), mission_result_sub, &mission_result); + orb_copy(ORB_ID(mission_result), mission_result_sub, &_mission_result); - if (_verbose) { warnx("Got mission result: new current: %d", mission_result.index_current_mission); } + if (_verbose) { warnx("WPM: got mission result, new current: %d", _mission_result.index_current_mission); } - if (mission_result.mission_reached) { - mavlink_wpm_send_waypoint_reached((uint16_t)mission_result.mission_index_reached); + if (_mission_result.mission_reached) { + mavlink_wpm_send_waypoint_reached((uint16_t)_mission_result.mission_index_reached); } - mavlink_wpm_send_waypoint_current((uint16_t)mission_result.index_current_mission); + mavlink_wpm_send_waypoint_current((uint16_t)_mission_result.index_current_mission); } else { if (slow_rate_limiter.check(t)) { - mavlink_wpm_send_waypoint_current((uint16_t)mission_result.index_current_mission); + mavlink_wpm_send_waypoint_current((uint16_t)_mission_result.index_current_mission); } } diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 61fd7afe2..5d7273abd 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -50,6 +50,7 @@ #include #include +#include #include "mavlink_bridge_header.h" #include "mavlink_orb_subscription.h" @@ -238,7 +239,8 @@ private: MavlinkStream *_streams; orb_advert_t _mission_pub; - struct mission_s mission; + struct mission_s _mission; + struct mission_result_s _mission_result; MAVLINK_MODE _mode; uint8_t _mavlink_wpm_comp_id; -- cgit v1.2.3 From 7d05f2df7cf50dea6d2960001b5b0af7236f9e5e Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Fri, 13 Jun 2014 20:38:43 -0400 Subject: Added support for velocity setpoint in mavlink_receiver and mc_pos_control --- src/modules/mavlink/mavlink_receiver.cpp | 36 +++++++++++++++++++++- src/modules/mavlink/mavlink_receiver.h | 2 ++ src/modules/mc_pos_control/mc_pos_control_main.cpp | 28 ++++++++++++++++- 3 files changed, 64 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index de9a6e7ad..8a00509a4 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -103,6 +103,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) : _flow_pub(-1), _offboard_control_sp_pub(-1), _local_pos_sp_pub(-1), + _global_vel_sp_pub(-1), _att_sp_pub(-1), _rates_sp_pub(-1), _vicon_position_pub(-1), @@ -450,6 +451,11 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message _rates_sp_pub = -1; } + if (_global_vel_sp_pub > 0) { + close(_global_vel_sp_pub); + _global_vel_sp_pub = -1; + } + if (_local_pos_sp_pub < 0) { _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp_pub); @@ -458,7 +464,30 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message } } else if (_control_mode.flag_control_velocity_enabled) { - // TODO + /* velocity control */ + struct vehicle_global_velocity_setpoint_s global_vel_sp; + memset(&global_vel_sp, 0, sizeof(&global_vel_sp)); + + global_vel_sp.vx = offboard_control_sp.p1; + global_vel_sp.vy = offboard_control_sp.p2; + global_vel_sp.vz = offboard_control_sp.p3; + + if (_att_sp_pub > 0) { + close(_att_sp_pub); + _att_sp_pub = -1; + } + + if (_rates_sp_pub > 0) { + close(_rates_sp_pub); + _rates_sp_pub = -1; + } + + if (_global_vel_sp_pub < 0) { + _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint_s), &_global_vel_sp_pub); + + } else { + orb_publish(ORB_ID(vehicle_global_velocity_setpoint_s), _global_vel_sp_pub, &global_vel_sp); + } } else if (_control_mode.flag_control_attitude_enabled) { /* attitude control */ @@ -1038,6 +1067,11 @@ MavlinkReceiver::receive_thread(void *arg) _local_pos_sp_pub = -1; } + if (_global_vel_sp_pub > 0) { + close(_global_vel_sp_pub); + _global_vel_sp_pub = -1; + } + if (_att_sp_pub > 0) { close(_att_sp_pub); _att_sp_pub = -1; diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index db9e06461..a20cbc7e9 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -55,6 +55,7 @@ #include #include #include +#include #include #include #include @@ -138,6 +139,7 @@ private: orb_advert_t _flow_pub; orb_advert_t _offboard_control_sp_pub; orb_advert_t _local_pos_sp_pub; + orb_advert_t _global_vel_sp_pub; orb_advert_t _att_sp_pub; orb_advert_t _rates_sp_pub; orb_advert_t _vicon_position_pub; diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 9d9d2a7c0..53394b41c 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -119,6 +119,7 @@ private: int _local_pos_sub; /**< vehicle local position */ int _pos_sp_triplet_sub; /**< position setpoint triplet */ int _local_pos_sp_sub; /**< offboard local position setpoint */ + int _global_vel_sp_sub; /**< offboard global velocity setpoint */ orb_advert_t _att_sp_pub; /**< attitude setpoint publication */ orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */ @@ -257,6 +258,7 @@ MulticopterPositionControl::MulticopterPositionControl() : _manual_sub(-1), _arming_sub(-1), _local_pos_sub(-1), + _global_vel_sp_sub(-1), _pos_sp_triplet_sub(-1), /* publications */ @@ -784,6 +786,24 @@ MulticopterPositionControl::task_main() _vel_sp(2) = _params.land_speed; } + /* Offboard velocity control mode */ + if (_control_mode.flag_control_offboard_enabled) { + bool updated; + orb_check(_global_vel_sp_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_sub, &_global_vel_sp); + } + + if (!_control_mode.flag_control_altitude_enabled && _control_mode.flag_control_climb_rate_enabled) { + _vel_sp(2) = _global_vel_sp.vz; + } + + if (!_control_mode.flag_control_position_enabled && _control_mode.flag_control_velocity_enabled) { + _vel_sp(0) = _global_vel_sp.vx; + _vel_sp(1) = _global_vel_sp.vy; + } + if (!_control_mode.flag_control_manual_enabled) { /* limit 3D speed only in non-manual modes */ float vel_sp_norm = _vel_sp.edivide(_params.vel_max).length(); @@ -801,10 +821,16 @@ MulticopterPositionControl::task_main() if (_global_vel_sp_pub > 0) { orb_publish(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_pub, &_global_vel_sp); - } else { + } else if (!_control_mode.flag_control_offboard_enabled) { _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &_global_vel_sp); } + /* Close fd to let offboard vel sp be advertised in mavlink receiver */ + if (_control_mode.flag_control_offboard_enabled && _global_vel_sp_pub > 0) { + close (_global_vel_sp); + _global_vel_sp_pub = -1; + } + if (_control_mode.flag_control_climb_rate_enabled || _control_mode.flag_control_velocity_enabled) { /* reset integrals if needed */ if (_control_mode.flag_control_climb_rate_enabled) { -- cgit v1.2.3 From 6cf890b46b5a112ed20b3f8ed7be7b658d5c4a8c Mon Sep 17 00:00:00 2001 From: andre-nguyen Date: Sat, 14 Jun 2014 15:27:07 -0400 Subject: indentation and fix commander flags. It's impossible to control position at the same time as attitude so we have to disable some things. My logic is that all the control flags for position control should be opposite of the attitude control mode. --- src/modules/commander/commander.cpp | 4 ++-- src/modules/mc_pos_control/mc_pos_control_main.cpp | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 3da43a792..2c36b2e6c 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1834,8 +1834,8 @@ set_control_mode() control_mode.flag_control_velocity_enabled = true; break; case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: - control_mode.flag_control_rates_enabled = true; - control_mode.flag_control_attitude_enabled = true; + control_mode.flag_control_rates_enabled = false; + control_mode.flag_control_attitude_enabled = false; control_mode.flag_control_altitude_enabled = true; control_mode.flag_control_climb_rate_enabled = true; control_mode.flag_control_position_enabled = true; diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 9d9d2a7c0..6721d017d 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -679,12 +679,12 @@ MulticopterPositionControl::task_main() /* Make sure position control is selected i.e. not only velocity control */ if (_control_mode.flag_control_position_enabled) { - _pos_sp(0) = _local_pos_sp.x; - _pos_sp(1) = _local_pos_sp.y; + _pos_sp(0) = _local_pos_sp.x; + _pos_sp(1) = _local_pos_sp.y; } if (_control_mode.flag_control_altitude_enabled) { - _pos_sp(2) = _local_pos_sp.z; + _pos_sp(2) = _local_pos_sp.z; } _att_sp.yaw_body = _local_pos_sp.yaw; -- cgit v1.2.3 From 128ec447ad43d5a25abcbdda6de01ca7ebc681cf Mon Sep 17 00:00:00 2001 From: Benjamin O'Connell-Armand Date: Sat, 14 Jun 2014 15:50:21 -0400 Subject: Fix various compilation issue --- src/modules/mavlink/mavlink_receiver.cpp | 8 ++++---- src/modules/mc_pos_control/mc_pos_control_main.cpp | 9 +++++---- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 8a00509a4..c95ee880c 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -390,14 +390,14 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message break; } - if (m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES || m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) { + if (ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES || ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) { offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX; offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX; offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX; offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX; - } else if (m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY || m1_mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) { + } else if (ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY || ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) { /*Temporary hack to use set_quad_swarm_roll_pitch_yaw_thrust msg for position or velocity */ /* Converts INT16 centimeters to float meters */ @@ -483,10 +483,10 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message } if (_global_vel_sp_pub < 0) { - _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint_s), &_global_vel_sp_pub); + _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &_global_vel_sp_pub); } else { - orb_publish(ORB_ID(vehicle_global_velocity_setpoint_s), _global_vel_sp_pub, &global_vel_sp); + orb_publish(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_pub, &global_vel_sp); } } else if (_control_mode.flag_control_attitude_enabled) { diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 53394b41c..86112fa21 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -117,9 +117,9 @@ private: int _manual_sub; /**< notification of manual control updates */ int _arming_sub; /**< arming status of outputs */ int _local_pos_sub; /**< vehicle local position */ - int _pos_sp_triplet_sub; /**< position setpoint triplet */ - int _local_pos_sp_sub; /**< offboard local position setpoint */ - int _global_vel_sp_sub; /**< offboard global velocity setpoint */ + int _pos_sp_triplet_sub; /**< position setpoint triplet */ + int _local_pos_sp_sub; /**< offboard local position setpoint */ + int _global_vel_sp_sub; /**< offboard global velocity setpoint */ orb_advert_t _att_sp_pub; /**< attitude setpoint publication */ orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */ @@ -802,6 +802,7 @@ MulticopterPositionControl::task_main() if (!_control_mode.flag_control_position_enabled && _control_mode.flag_control_velocity_enabled) { _vel_sp(0) = _global_vel_sp.vx; _vel_sp(1) = _global_vel_sp.vy; + } } if (!_control_mode.flag_control_manual_enabled) { @@ -827,7 +828,7 @@ MulticopterPositionControl::task_main() /* Close fd to let offboard vel sp be advertised in mavlink receiver */ if (_control_mode.flag_control_offboard_enabled && _global_vel_sp_pub > 0) { - close (_global_vel_sp); + close(_global_vel_sp_pub); _global_vel_sp_pub = -1; } -- cgit v1.2.3 From 5be741607c0d8d477ff30c7639edbd3bce427e7b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 14 Jun 2014 23:57:29 +0200 Subject: mavlink: mission manager moved to separate class and reworked --- src/modules/commander/commander.cpp | 25 +- src/modules/mavlink/mavlink_main.cpp | 766 +++------------------------- src/modules/mavlink/mavlink_main.h | 92 +--- src/modules/mavlink/mavlink_mission.cpp | 823 +++++++++++++++++++++++++++++++ src/modules/mavlink/mavlink_mission.h | 176 +++++++ src/modules/mavlink/mavlink_receiver.cpp | 13 +- src/modules/mavlink/mavlink_receiver.h | 2 - src/modules/mavlink/module.mk | 1 + src/modules/mavlink/util.h | 53 -- src/modules/mavlink/waypoints.h | 111 ----- src/modules/navigator/mission.cpp | 107 ++-- src/modules/navigator/mission.h | 2 + src/modules/uORB/topics/mission.h | 6 +- src/modules/uORB/topics/mission_result.h | 8 +- 14 files changed, 1168 insertions(+), 1017 deletions(-) create mode 100644 src/modules/mavlink/mavlink_mission.cpp create mode 100644 src/modules/mavlink/mavlink_mission.h delete mode 100644 src/modules/mavlink/util.h delete mode 100644 src/modules/mavlink/waypoints.h diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index d2f8c2994..379ce45fb 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -715,17 +715,27 @@ int commander_thread_main(int argc, char *argv[]) struct home_position_s home; memset(&home, 0, sizeof(home)); - /* init mission state */ + /* init mission state, do it here to allow navigator to use stored mission even if mavlink failed to start */ + orb_advert_t mission_pub = -1; mission_s mission; if (dm_read(DM_KEY_MISSION_STATE, 0, &mission, sizeof(mission_s)) == sizeof(mission_s)) { if (mission.dataman_id >= 0 && mission.dataman_id <= 1) { - mavlink_log_info(mavlink_fd, "[cmd] dataman ID: %i, count: %u, current: %i", - mission.dataman_id, mission.count, mission.current_index); - orb_advert_t mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission); - close(mission_pub); + warnx("loaded mission state: dataman_id=%d, count=%u, current=%d", mission.dataman_id, mission.count, mission.current_seq); + mavlink_log_info(mavlink_fd, "[cmd] dataman_id=%d, count=%u, current=%d", + mission.dataman_id, mission.count, mission.current_seq); } else { + warnx("reading mission state failed"); mavlink_log_info(mavlink_fd, "[cmd] reading mission state failed"); + + /* initialize mission state in dataman */ + mission.dataman_id = 0; + mission.count = 0; + mission.current_seq = 0; + dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission, sizeof(mission_s)); } + + mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission); + orb_publish(ORB_ID(offboard_mission), mission_pub, &mission); } mavlink_log_info(mavlink_fd, "[cmd] started"); @@ -1310,7 +1320,7 @@ int commander_thread_main(int argc, char *argv[]) status.rc_signal_lost = true; status_changed = true; - if (!(status.set_nav_state == NAVIGATION_STATE_AUTO_MISSION && !mission_result.mission_finished)) { + if (!(status.set_nav_state == NAVIGATION_STATE_AUTO_MISSION && !mission_result.finished)) { /* if we have a global position, we can switch to RTL, if not, we can try to land */ if (status.condition_global_position_valid) { @@ -1327,7 +1337,7 @@ int commander_thread_main(int argc, char *argv[]) /* hack to detect if we finished a mission after we lost RC, so that we can trigger RTL now */ if (status.rc_signal_lost && status.set_nav_state == NAVIGATION_STATE_AUTO_MISSION && - mission_result.mission_finished && status.failsafe_state != FAILSAFE_STATE_RC_LOSS) { + mission_result.finished && status.failsafe_state != FAILSAFE_STATE_RC_LOSS) { /* if we have a global position, we can switch to RTL, if not, we can try to land */ if (status.condition_global_position_valid) { status.failsafe_state = FAILSAFE_STATE_RC_LOSS; @@ -1488,6 +1498,7 @@ int commander_thread_main(int argc, char *argv[]) close(diff_pres_sub); close(param_changed_sub); close(battery_sub); + close(mission_pub); thread_running = false; diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 126c4dfc6..f8a31a4ad 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -102,6 +102,8 @@ static struct file_operations fops; */ extern "C" __EXPORT int mavlink_main(int argc, char *argv[]); +extern mavlink_system_t mavlink_system; + static uint64_t last_write_success_times[6] = {0}; static uint64_t last_write_try_times[6] = {0}; @@ -200,9 +202,6 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length last_write_success_times[(unsigned)channel] = last_write_try_times[(unsigned)channel]; } } - - - } static void usage(void); @@ -221,6 +220,7 @@ Mavlink::Mavlink() : _main_loop_delay(1000), _subscriptions(nullptr), _streams(nullptr), + _mission_result_sub(-1), _mission_pub(-1), _mode(MAVLINK_MODE_NORMAL), _total_counter(0), @@ -238,12 +238,11 @@ Mavlink::Mavlink() : _param_component_id(0), _param_system_type(0), _param_use_hil_gps(0), + _mission_manager(nullptr), /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "mavlink")) { - _wpm = &_wpm_s; - fops.ioctl = (int (*)(file *, int, long unsigned int))&mavlink_dev_ioctl; _instance_id = Mavlink::instance_count(); @@ -421,7 +420,7 @@ Mavlink::instance_exists(const char *device_name, Mavlink *self) } void -Mavlink::forward_message(mavlink_message_t *msg, Mavlink *self) +Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self) { Mavlink *inst; @@ -497,7 +496,6 @@ Mavlink::mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg) void Mavlink::mavlink_update_system(void) { - if (!_param_initialized) { _param_system_id = param_find("MAV_SYS_ID"); _param_component_id = param_find("MAV_COMP_ID"); @@ -701,9 +699,32 @@ Mavlink::set_hil_enabled(bool hil_enabled) return ret; } -extern mavlink_system_t mavlink_system; +void +Mavlink::send_message(const mavlink_message_t *msg) +{ + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; -int Mavlink::mavlink_pm_queued_send() + uint16_t len = mavlink_msg_to_send_buffer(buf, msg); + mavlink_send_uart_bytes(_channel, buf, len); +} + +void +Mavlink::handle_message(const mavlink_message_t *msg) +{ + /* handle packet with mission manager */ + _mission_manager->handle_message(msg); + + /* handle packet with parameter component */ + mavlink_pm_message_handler(_channel, msg); + + if (get_forwarding_on()) { + /* forward any messages to other mavlink instances */ + Mavlink::forward_message(msg, this); + } +} + +int +Mavlink::mavlink_pm_queued_send() { if (_mavlink_param_queue_index < param_count()) { mavlink_pm_send_param(param_for_index(_mavlink_param_queue_index)); @@ -780,7 +801,7 @@ int Mavlink::mavlink_pm_send_param(param_t param) mavlink_type, param_count(), param_get_index(param)); - mavlink_missionlib_send_message(&tx_msg); + send_message(&tx_msg); return OK; } @@ -794,7 +815,7 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav (req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) { /* Start sending parameters */ mavlink_pm_start_queued_send(); - mavlink_missionlib_send_gcs_string("[mavlink pm] sending list"); + send_statustext("[mavlink pm] sending list"); } } break; @@ -818,7 +839,7 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav if (param == PARAM_INVALID) { char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; sprintf(buf, "[pm] unknown: %s", name); - mavlink_missionlib_send_gcs_string(buf); + send_statustext(buf); } else { /* set and send parameter */ @@ -854,677 +875,18 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav } } -void Mavlink::publish_mission() -{ - /* Initialize mission publication if necessary */ - if (_mission_pub < 0) { - _mission_pub = orb_advertise(ORB_ID(offboard_mission), &_mission); - - } else { - orb_publish(ORB_ID(offboard_mission), _mission_pub, &_mission); - } -} - -int Mavlink::map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item) -{ - /* only support global waypoints for now */ - switch (mavlink_mission_item->frame) { - case MAV_FRAME_GLOBAL: - mission_item->lat = (double)mavlink_mission_item->x; - mission_item->lon = (double)mavlink_mission_item->y; - mission_item->altitude = mavlink_mission_item->z; - mission_item->altitude_is_relative = false; - break; - - case MAV_FRAME_GLOBAL_RELATIVE_ALT: - mission_item->lat = (double)mavlink_mission_item->x; - mission_item->lon = (double)mavlink_mission_item->y; - mission_item->altitude = mavlink_mission_item->z; - mission_item->altitude_is_relative = true; - break; - - case MAV_FRAME_LOCAL_NED: - case MAV_FRAME_LOCAL_ENU: - return MAV_MISSION_UNSUPPORTED_FRAME; - - case MAV_FRAME_MISSION: - default: - return MAV_MISSION_ERROR; - } - - switch (mavlink_mission_item->command) { - case MAV_CMD_NAV_TAKEOFF: - mission_item->pitch_min = mavlink_mission_item->param1; - break; - case MAV_CMD_DO_JUMP: - mission_item->do_jump_mission_index = mavlink_mission_item->param1; - mission_item->do_jump_repeat_count = mavlink_mission_item->param2; - break; - default: - mission_item->acceptance_radius = mavlink_mission_item->param2; - mission_item->time_inside = mavlink_mission_item->param1; - break; - } - - mission_item->yaw = _wrap_pi(mavlink_mission_item->param4 * M_DEG_TO_RAD_F); - mission_item->loiter_radius = fabsf(mavlink_mission_item->param3); - mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */ - mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command; - - mission_item->autocontinue = mavlink_mission_item->autocontinue; - // mission_item->index = mavlink_mission_item->seq; - mission_item->origin = ORIGIN_MAVLINK; - - /* reset DO_JUMP count */ - mission_item->do_jump_current_count = 0; - - return OK; -} - -int Mavlink::map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item) -{ - if (mission_item->altitude_is_relative) { - mavlink_mission_item->frame = MAV_FRAME_GLOBAL; - - } else { - mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; - } - - switch (mission_item->nav_cmd) { - case NAV_CMD_TAKEOFF: - mavlink_mission_item->param1 = mission_item->pitch_min; - break; - - case NAV_CMD_DO_JUMP: - mavlink_mission_item->param1 = mission_item->do_jump_mission_index; - mavlink_mission_item->param2 = mission_item->do_jump_repeat_count; - break; - - default: - mavlink_mission_item->param2 = mission_item->acceptance_radius; - mavlink_mission_item->param1 = mission_item->time_inside; - break; - } - - mavlink_mission_item->x = (float)mission_item->lat; - mavlink_mission_item->y = (float)mission_item->lon; - mavlink_mission_item->z = mission_item->altitude; - - mavlink_mission_item->param4 = mission_item->yaw * M_RAD_TO_DEG_F; - mavlink_mission_item->param3 = mission_item->loiter_radius * (float)mission_item->loiter_direction; - mavlink_mission_item->command = mission_item->nav_cmd; - mavlink_mission_item->autocontinue = mission_item->autocontinue; - // mavlink_mission_item->seq = mission_item->index; - - return OK; -} - -void Mavlink::mavlink_wpm_init(mavlink_wpm_storage *state) -{ - /* get offboard_mission topic */ - int mission_sub = orb_subscribe(ORB_ID(offboard_mission)); - if (orb_copy(ORB_ID(offboard_mission), mission_sub, &_mission)) { - /* error getting topic, init to safe values */ - _mission.dataman_id = 0; - _mission.count = 0; - _mission.current_index = -1; - } - close(mission_sub); - - /* init WPM state */ - state->size = _mission.count; - state->max_size = MAVLINK_WPM_MAX_WP_COUNT; - state->dataman_id = _mission.dataman_id; - state->current_state = MAVLINK_WPM_STATE_IDLE; - state->current_partner_sysid = 0; - state->current_partner_compid = 0; - state->current_dataman_id = 0; - state->timestamp_lastaction = 0; - state->timestamp_last_send_setpoint = 0; - state->timestamp_last_send_request = 0; - state->action_timeout = MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT; - state->retry_timeout = MAVLINK_WPM_RETRY_TIMEOUT_DEFAULT; - - warnx("wpm init: dataman_id=%d, count=%u, current=%d", state->dataman_id, state->size, _mission.current_index); -} - -/* - * @brief Sends an waypoint ack message - */ -void Mavlink::mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type) -{ - mavlink_message_t msg; - mavlink_mission_ack_t wpa; - - wpa.target_system = sysid; - wpa.target_component = compid; - wpa.type = type; - - mavlink_msg_mission_ack_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpa); - mavlink_missionlib_send_message(&msg); - - if (_verbose) { warnx("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system); } -} - -/* - * @brief Broadcasts the new target waypoint and directs the MAV to fly there - * - * This function broadcasts its new active waypoint sequence number and - * 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. - */ -void Mavlink::mavlink_wpm_send_waypoint_current(uint16_t seq) -{ - if (seq < _wpm->size) { - mavlink_message_t msg; - mavlink_mission_current_t wpc; - - wpc.seq = seq; - - mavlink_msg_mission_current_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpc); - mavlink_missionlib_send_message(&msg); - - } else if (seq == 0 && _wpm->size == 0) { - /* don't broadcast if no WPs */ - - } else { - if (_verbose) { warnx("WPM: Send WAYPOINT_CURRENT ERROR: seq %u out of bounds", seq); } - - mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds"); - } -} - -void Mavlink::mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count) -{ - mavlink_message_t msg; - mavlink_mission_count_t wpc; - - wpc.target_system = sysid; - wpc.target_component = compid; - wpc.count = _wpm->size; - - mavlink_msg_mission_count_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpc); - mavlink_missionlib_send_message(&msg); - - if (_verbose) { warnx("WPM: Send WAYPOINT_COUNT %u to ID %u", wpc.count, wpc.target_system); } -} - -void Mavlink::mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq) -{ - dm_item_t dm_item = _wpm->dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; - struct mission_item_s mission_item; - - if (dm_read(dm_item, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { - - /* create mission_item_s from mavlink_mission_item_t */ - mavlink_mission_item_t wp; - map_mission_item_to_mavlink_mission_item(&mission_item, &wp); - - mavlink_message_t msg; - wp.target_system = sysid; - wp.target_component = compid; - wp.seq = seq; - wp.current = (_mission_result.index_current_mission == seq) ? 1 : 0; - mavlink_msg_mission_item_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wp); - mavlink_missionlib_send_message(&msg); - - if (_verbose) { warnx("WPM: Send WAYPOINT seq %u to ID %u", wp.seq, wp.target_system); } - - } else { - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); - mavlink_missionlib_send_gcs_string("#audio: Unable to read from micro SD"); - - if (_verbose) { warnx("WPM: Send WAYPOINT ERROR: could not read seq %u from dataman ID %i", seq, _wpm->dataman_id); } - } -} - -void Mavlink::mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq) -{ - if (seq < _wpm->max_size) { - mavlink_message_t msg; - mavlink_mission_request_t wpr; - wpr.target_system = sysid; - wpr.target_component = compid; - wpr.seq = seq; - mavlink_msg_mission_request_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wpr); - mavlink_missionlib_send_message(&msg); - _wpm->timestamp_last_send_request = hrt_absolute_time(); - - if (_verbose) { warnx("WPM: Send WAYPOINT_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system); } - - } else { - mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity"); - - if (_verbose) { warnx("WPM: Send WAYPINT_REQUEST ERROR: seq %u exceeds list capacity", seq); } - } -} - -/* - * @brief emits a message that a waypoint reached - * - * This function broadcasts a message that a waypoint is reached. - * - * @param seq The waypoint sequence number the MAV has reached. - */ -void Mavlink::mavlink_wpm_send_waypoint_reached(uint16_t seq) -{ - mavlink_message_t msg; - mavlink_mission_item_reached_t wp_reached; - - wp_reached.seq = seq; - - mavlink_msg_mission_item_reached_encode_chan(mavlink_system.sysid, _mavlink_wpm_comp_id, _channel, &msg, &wp_reached); - mavlink_missionlib_send_message(&msg); - - if (_verbose) { warnx("WPM: Send WAYPOINT_REACHED seq %u", wp_reached.seq); } -} - -void Mavlink::mavlink_waypoint_eventloop(uint64_t now) -{ - /* check for timed-out operations */ - if (now - _wpm->timestamp_lastaction > _wpm->action_timeout && _wpm->current_state != MAVLINK_WPM_STATE_IDLE) { - - mavlink_missionlib_send_gcs_string("Operation timeout"); - - if (_verbose) { warnx("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _wpm->current_state); } - - _wpm->current_state = MAVLINK_WPM_STATE_IDLE; - _wpm->current_partner_sysid = 0; - _wpm->current_partner_compid = 0; - - } else if (now - _wpm->timestamp_last_send_request > _wpm->retry_timeout && _wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) { - /* try to get WP again after short timeout */ - mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); - } -} - - -void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) -{ - uint64_t now = hrt_absolute_time(); - - switch (msg->msgid) { - - case MAVLINK_MSG_ID_MISSION_ACK: { - mavlink_mission_ack_t wpa; - mavlink_msg_mission_ack_decode(msg, &wpa); - - if (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/) { - if ((msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid)) { - _wpm->timestamp_lastaction = now; - - if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST || _wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) { - if (_wpm->current_wp_id == _wpm->size - 1) { - if (_verbose) { warnx("WPM: MISSION_ACK all items sent, switch to MAVLINK_WPM_STATE_IDLE"); } - - _wpm->current_state = MAVLINK_WPM_STATE_IDLE; - _wpm->current_wp_id = 0; - } - } - - } else { - mavlink_missionlib_send_gcs_string("REJ. WP CMD: partner id mismatch"); - - if (_verbose) { warnx("WPM: MISSION_ACK ERROR: rejected, partner ID mismatch"); } - } - } - break; - } - - case MAVLINK_MSG_ID_MISSION_SET_CURRENT: { - mavlink_mission_set_current_t wpc; - mavlink_msg_mission_set_current_decode(msg, &wpc); - - if (wpc.target_system == mavlink_system.sysid /*&& wpc.target_component == mavlink_wpm_comp_id*/) { - _wpm->timestamp_lastaction = now; - - if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE) { - if (wpc.seq < _wpm->size) { - if (_verbose) { warnx("WPM: MISSION_SET_CURRENT OK (%d)", wpc.seq); } - - _mission.current_index = wpc.seq; - publish_mission(); - - } else { - if (_verbose) { warnx("WPM: MISSION_SET_CURRENT ERROR: not in list (%d)", wpc.seq); } - - mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list"); - } - - } else { - if (_verbose) { warnx("WPM: MISSION_SET_CURRENT ERROR: busy"); } - - mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Busy"); - } - } - - break; - } - - case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: { - mavlink_mission_request_list_t wprl; - mavlink_msg_mission_request_list_decode(msg, &wprl); - - if (wprl.target_system == mavlink_system.sysid /*&& wprl.target_component == mavlink_wpm_comp_id*/) { - _wpm->timestamp_lastaction = now; - - if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE || _wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) { - if (_wpm->size > 0) { - _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) { warnx("WPM: MISSION_REQUEST_LIST nothing to send, mission is empty"); } - } - - _wpm->current_count = _wpm->size; - mavlink_wpm_send_waypoint_count(msg->sysid, msg->compid, _wpm->current_count); - - } else { - if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST ERROR: busy"); } - - mavlink_missionlib_send_gcs_string("IGN REQUEST LIST: Busy"); - } - } - - break; - } - - case MAVLINK_MSG_ID_MISSION_REQUEST: { - mavlink_mission_request_t wpr; - mavlink_msg_mission_request_decode(msg, &wpr); - - if (wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) { - if (msg->sysid == _wpm->current_partner_sysid && msg->compid == _wpm->current_partner_compid) { - _wpm->timestamp_lastaction = now; - - if (wpr.seq >= _wpm->size) { - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: ignored, requested seq %u was out of bounds [0 %d]", wpr.seq, _wpm->size - 1); } - - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP not in list"); - break; - } - - /* - * 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) - */ - if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) { - if (wpr.seq == 0) { - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u from ID %u, changing state to MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } - - _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS; - - } else { - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: first id != 0 (%d)", wpr.seq); } - - mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0"); - break; - } - - } else if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST_SENDWPS) { - if (wpr.seq == _wpm->current_wp_id) { - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u (again) from ID %u, staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } - - } else if (wpr.seq == _wpm->current_wp_id + 1) { - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u from ID %u, staying in state MAVLINK_WPM_STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } - - } else { - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u from ID %u unexpected, should be %i or %i", wpr.seq, msg->sysid, _wpm->current_wp_id, _wpm->current_wp_id + 1); } - - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Req. WP was unexpected"); - break; - } - - } else { - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: busy (state %d).", _wpm->current_state); } - - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); - break; - } - - _wpm->current_wp_id = wpr.seq; - _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS; - - if (wpr.seq < _wpm->size) { - mavlink_wpm_send_waypoint(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); - - } else { - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u out of bounds", wpr.seq); } - - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); - } - - } else { - mavlink_missionlib_send_gcs_string("REJ. WP CMD: partner id mismatch"); - - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: rejected, partner ID mismatch"); } - } - } - break; - } - - case MAVLINK_MSG_ID_MISSION_COUNT: { - mavlink_mission_count_t wpc; - mavlink_msg_mission_count_decode(msg, &wpc); - - if (wpc.target_system == mavlink_system.sysid/* && wpc.target_component == mavlink_wpm_comp_id*/) { - _wpm->timestamp_lastaction = now; - - if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE) { - - if (wpc.count > NUM_MISSIONS_SUPPORTED) { - if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: too many waypoints (%d), supported: %d", wpc.count, NUM_MISSIONS_SUPPORTED); } - - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_NO_SPACE); - break; - } - - if (wpc.count == 0) { - if (_verbose) { warnx("WPM: MISSION_COUNT 0, clearing waypoints list and staying in state MAVLINK_WPM_STATE_IDLE"); } - - mavlink_missionlib_send_gcs_string("WP COUNT 0: CLEAR MISSION"); - break; - } - - if (_verbose) { warnx("WPM: MISSION_COUNT %u from ID %u, changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid); } - - } else if (_wpm->current_state == MAVLINK_WPM_STATE_GETLIST) { - - if (_wpm->current_wp_id == 0) { - /* looks like our WAYPOINT_REQUEST was lost, try again */ - if (_verbose) { warnx("WPM: MISSION_COUNT %u (again) from ID %u", wpc.count, msg->sysid); } - - mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN"); - - } else { - if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _wpm->current_wp_id); } - - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); - break; - } - - } else { - if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, state %i", _wpm->current_state); } - - mavlink_missionlib_send_gcs_string("IGN MISSION_COUNT CMD: Busy"); - break; - } - - _wpm->current_state = MAVLINK_WPM_STATE_GETLIST; - _wpm->current_wp_id = 0; - _wpm->current_partner_sysid = msg->sysid; - _wpm->current_partner_compid = msg->compid; - _wpm->current_count = wpc.count; - _wpm->current_dataman_id = _wpm->dataman_id == 0 ? 1 : 0; // use inactive storage for transmission - - _mission.current_index = -1; - - mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); - } - } - break; - - case MAVLINK_MSG_ID_MISSION_ITEM: { - mavlink_mission_item_t wp; - mavlink_msg_mission_item_decode(msg, &wp); - - if (wp.target_system == mavlink_system.sysid && wp.target_component == _mavlink_wpm_comp_id) { - _wpm->timestamp_lastaction = now; - - /* Ensure that we are in the correct state and that the first waypoint has id 0 - * and the following waypoints have the correct ids - */ - if (_wpm->current_state == MAVLINK_WPM_STATE_GETLIST) { - if (wp.seq != 0) { - if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: first item seq != 0 (%d)", wp.seq); } - break; - } - - } else if (_wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) { - if (wp.seq >= _wpm->current_count) { - if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: first item seq %d out of bounds [0 %d]", wp.seq, _wpm->current_count - 1); } - - mavlink_missionlib_send_gcs_string("Ignored MISSION_ITEM WP out of bounds"); - break; - } - - if (wp.seq != _wpm->current_wp_id) { - if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u was not the expected %u", wp.seq, _wpm->current_wp_id); } - - mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); - break; - } - } - - _wpm->current_state = MAVLINK_WPM_STATE_GETLIST_GETWPS; - - struct mission_item_s mission_item; - int ret = map_mavlink_mission_item_to_mission_item(&wp, &mission_item); - - if (ret != OK) { - if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq); } - - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, ret); - _wpm->current_state = MAVLINK_WPM_STATE_IDLE; - break; - } - - dm_item_t dm_item = _wpm->current_dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; - - if (dm_write(dm_item, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, sizeof(struct mission_item_s)) != sizeof(struct mission_item_s)) { - if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _wpm->current_dataman_id); } - - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); - mavlink_missionlib_send_gcs_string("#audio: Unable to write on micro SD"); - _wpm->current_state = MAVLINK_WPM_STATE_IDLE; - break; - } - - /* waypoint marked as current */ - if (wp.current) { - _mission.current_index = wp.seq; - } - - if (_verbose) { warnx("WPM: MISSION_ITEM seq %u received", wp.seq); } - - _wpm->current_wp_id = wp.seq + 1; - - if (_wpm->current_wp_id == _wpm->current_count && _wpm->current_state == MAVLINK_WPM_STATE_GETLIST_GETWPS) { - /* got all new mission items successfully */ - if (_verbose) { warnx("WPM: MISSION_ITEM got all %u items, changing state to MAVLINK_WPM_STATE_IDLE", _wpm->current_count); } - - _wpm->current_state = MAVLINK_WPM_STATE_IDLE; - - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); - - /* update WPM state */ - _wpm->dataman_id = _wpm->current_dataman_id; - _wpm->size = _wpm->current_count; - - /* update mission topic */ - _mission.dataman_id = _wpm->dataman_id; - _mission.count = _wpm->current_count; - - publish_mission(); - - } else { - /* request next item */ - mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); - } - } - break; - } - - case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: { - mavlink_mission_clear_all_t wpca; - mavlink_msg_mission_clear_all_decode(msg, &wpca); - - if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */) { - - if (_wpm->current_state == MAVLINK_WPM_STATE_IDLE) { - /* clear only active dataman storage, don't change storage id */ - dm_item_t dm_id = _wpm->dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; - - if (dm_clear(dm_id) == OK) { - if (_verbose) { warnx("WPM: CLEAR_ALL OK"); } - - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ACCEPTED); - - /* update WPM state */ - _wpm->timestamp_lastaction = now; - _wpm->size = 0; - - /* update mission topic */ - _mission.dataman_id = _wpm->dataman_id; - _mission.count = 0; - _mission.current_index = -1; - - publish_mission(); - - } else { - if (_verbose) { warnx("WPM: CLEAR_ALL ERROR: can't clear dataman mission storage"); } - - mavlink_wpm_send_waypoint_ack(_wpm->current_partner_sysid, _wpm->current_partner_compid, MAV_MISSION_ERROR); - } - - } else { - mavlink_missionlib_send_gcs_string("IGN WP CLEAR CMD: Busy"); - - if (_verbose) { warnx("WPM: CLEAR_ALL IGNORED: busy"); } - } - } - - break; - } - - default: { - /* other messages might should get caught by mavlink and others */ - break; - } - } -} - -void -Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg) +int +Mavlink::send_statustext(const char *string) { - uint8_t buf[MAVLINK_MAX_PACKET_LEN]; - - uint16_t len = mavlink_msg_to_send_buffer(buf, msg); - mavlink_send_uart_bytes(_channel, buf, len); + return send_statustext(MAV_SEVERITY_INFO, string); } - int -Mavlink::mavlink_missionlib_send_gcs_string(const char *string) +Mavlink::send_statustext(enum MAV_SEVERITY severity, const char *string) { const int len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN; mavlink_statustext_t statustext; - statustext.severity = MAV_SEVERITY_INFO; + statustext.severity = severity; int i = 0; @@ -1546,7 +908,7 @@ Mavlink::mavlink_missionlib_send_gcs_string(const char *string) return OK; } else { - return 1; + return ERROR; } } @@ -1684,7 +1046,7 @@ Mavlink::message_buffer_is_empty() bool -Mavlink::message_buffer_write(void *ptr, int size) +Mavlink::message_buffer_write(const void *ptr, int size) { // bytes available to write int available = _message_buffer.read_ptr - _message_buffer.write_ptr - 1; @@ -1751,7 +1113,7 @@ Mavlink::message_buffer_mark_read(int n) } void -Mavlink::pass_message(mavlink_message_t *msg) +Mavlink::pass_message(const mavlink_message_t *msg) { if (_passing_on) { /* size is 8 bytes plus variable payload */ @@ -1762,6 +1124,11 @@ Mavlink::pass_message(mavlink_message_t *msg) } } +float +Mavlink::get_rate_mult() +{ + return _datarate / 1000.0f; +} int Mavlink::task_main(int argc, char *argv[]) @@ -1879,8 +1246,6 @@ Mavlink::task_main(int argc, char *argv[]) break; } - _mavlink_wpm_comp_id = MAV_COMP_ID_MISSIONPLANNER; - warnx("data rate: %d Bytes/s, port: %s, baud: %d", _datarate, _device_name, _baudrate); /* flush stdout in case MAVLink is about to take it over */ @@ -1922,11 +1287,11 @@ Mavlink::task_main(int argc, char *argv[]) /* start the MAVLink receiver */ _receive_thread = MavlinkReceiver::receive_start(this); - /* initialize waypoint manager */ - mavlink_wpm_init(_wpm); + _mission_result_sub = orb_subscribe(ORB_ID(mission_result)); - int mission_result_sub = orb_subscribe(ORB_ID(mission_result)); - memset(&_mission_result, 0, sizeof(_mission_result)); + /* create mission manager */ + _mission_manager = new MavlinkMissionManager(this); + _mission_manager->set_verbose(_verbose); _task_running = true; @@ -1941,7 +1306,7 @@ Mavlink::task_main(int argc, char *argv[]) MavlinkCommandsStream commands_stream(this, _channel); /* add default streams depending on mode and intervals depending on datarate */ - float rate_mult = _datarate / 1000.0f; + float rate_mult = get_rate_mult(); configure_stream("HEARTBEAT", 1.0f); @@ -1976,7 +1341,6 @@ Mavlink::task_main(int argc, char *argv[]) /* don't send parameters on startup without request */ _mavlink_param_queue_index = param_count(); - MavlinkRateLimiter slow_rate_limiter(2000000.0f / rate_mult); MavlinkRateLimiter fast_rate_limiter(30000.0f / rate_mult); /* set main loop delay depending on data rate to minimize CPU overhead */ @@ -2030,36 +1394,16 @@ Mavlink::task_main(int argc, char *argv[]) stream->update(t); } - bool updated; - orb_check(mission_result_sub, &updated); - - if (updated) { - orb_copy(ORB_ID(mission_result), mission_result_sub, &_mission_result); - - if (_verbose) { warnx("WPM: got mission result, new current: %d", _mission_result.index_current_mission); } - - if (_mission_result.mission_reached) { - mavlink_wpm_send_waypoint_reached((uint16_t)_mission_result.mission_index_reached); - } - - mavlink_wpm_send_waypoint_current((uint16_t)_mission_result.index_current_mission); - - } else { - if (slow_rate_limiter.check(t)) { - mavlink_wpm_send_waypoint_current((uint16_t)_mission_result.index_current_mission); - } - } - if (fast_rate_limiter.check(t)) { mavlink_pm_queued_send(); - mavlink_waypoint_eventloop(hrt_absolute_time()); + _mission_manager->eventloop(); if (!mavlink_logbuffer_is_empty(&_logbuffer)) { struct mavlink_logmessage msg; int lb_ret = mavlink_logbuffer_read(&_logbuffer, &msg); if (lb_ret == OK) { - mavlink_missionlib_send_gcs_string(msg.text); + send_statustext(msg.text); } } } @@ -2093,11 +1437,11 @@ Mavlink::task_main(int argc, char *argv[]) } } - - perf_end(_loop_perf); } + delete _mission_manager; + delete _subscribe_to_stream; _subscribe_to_stream = nullptr; diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 5d7273abd..085a97d73 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -56,51 +56,7 @@ #include "mavlink_orb_subscription.h" #include "mavlink_stream.h" #include "mavlink_messages.h" - -// FIXME XXX - TO BE MOVED TO XML -enum MAVLINK_WPM_STATES { - MAVLINK_WPM_STATE_IDLE = 0, - MAVLINK_WPM_STATE_SENDLIST, - MAVLINK_WPM_STATE_SENDLIST_SENDWPS, - MAVLINK_WPM_STATE_GETLIST, - MAVLINK_WPM_STATE_GETLIST_GETWPS, - MAVLINK_WPM_STATE_GETLIST_GOTALL, - MAVLINK_WPM_STATE_ENUM_END -}; - -enum MAVLINK_WPM_CODES { - MAVLINK_WPM_CODE_OK = 0, - MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED, - MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED, - MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS, - MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED, - MAVLINK_WPM_CODE_ENUM_END -}; - - -#define MAVLINK_WPM_MAX_WP_COUNT 255 -#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication action timeout in useconds -#define MAVLINK_WPM_RETRY_TIMEOUT_DEFAULT 500000 ///< Protocol communication retry timeout in useconds -#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000000 ///< When to send a new setpoint -#define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40000 - - -struct mavlink_wpm_storage { - uint16_t size; ///< Count of waypoints in active mission - uint16_t max_size; ///< Maximal count of waypoints - int dataman_id; ///< Dataman storage ID for active mission - enum MAVLINK_WPM_STATES current_state; ///< Current waypoint manager state - int16_t current_wp_id; ///< Waypoint ID in current transmission - uint16_t current_count; ///< Waypoints count in current transmission - uint8_t current_partner_sysid; - uint8_t current_partner_compid; - int current_dataman_id; ///< Dataman storage ID for current transmission - uint64_t timestamp_lastaction; - uint64_t timestamp_last_send_setpoint; - uint64_t timestamp_last_send_request; - uint32_t action_timeout; - uint32_t retry_timeout; -}; +#include "mavlink_mission.h" class Mavlink @@ -143,7 +99,7 @@ public: static bool instance_exists(const char *device_name, Mavlink *self); - static void forward_message(mavlink_message_t *msg, Mavlink *self); + static void forward_message(const mavlink_message_t *msg, Mavlink *self); static int get_uart_fd(unsigned index); @@ -168,10 +124,6 @@ public: bool get_forwarding_on() { return _forwarding_on; } - /** - * Handle waypoint related messages. - */ - void mavlink_wpm_message_handler(const mavlink_message_t *msg); static int start_helper(int argc, char *argv[]); @@ -192,6 +144,10 @@ public: */ int set_hil_enabled(bool hil_enabled); + void send_message(const mavlink_message_t *msg); + + void handle_message(const mavlink_message_t *msg); + MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic); int get_instance_id(); @@ -209,6 +165,10 @@ public: int get_mavlink_fd() { return _mavlink_fd; } + int send_statustext(const char *string); + int send_statustext(enum MAV_SEVERITY severity, const char *string); + + float get_rate_mult(); /* Functions for waiting to start transmission until message received. */ void set_has_received_messages(bool received_messages) { _received_messages = received_messages; } @@ -238,12 +198,12 @@ private: MavlinkOrbSubscription *_subscriptions; MavlinkStream *_streams; + MavlinkMissionManager *_mission_manager; + orb_advert_t _mission_pub; - struct mission_s _mission; - struct mission_result_s _mission_result; + int _mission_result_sub; MAVLINK_MODE _mode; - uint8_t _mavlink_wpm_comp_id; mavlink_channel_t _channel; struct mavlink_logbuffer _logbuffer; @@ -251,10 +211,6 @@ private: pthread_t _receive_thread; - /* Allocate storage space for waypoints */ - mavlink_wpm_storage _wpm_s; - mavlink_wpm_storage *_wpm; - bool _verbose; bool _forwarding_on; bool _passing_on; @@ -336,20 +292,9 @@ private: void mavlink_update_system(); - void mavlink_waypoint_eventloop(uint64_t now); - void mavlink_wpm_send_waypoint_reached(uint16_t seq); - void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq); - void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq); - void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count); - void mavlink_wpm_send_waypoint_current(uint16_t seq); - void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type); - void mavlink_wpm_init(mavlink_wpm_storage *state); - int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item); - int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item); - void publish_mission(); - - void mavlink_missionlib_send_message(mavlink_message_t *msg); - int mavlink_missionlib_send_gcs_string(const char *string); + uint8_t get_system_id(); + + uint8_t get_component_id(); int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb); @@ -364,13 +309,13 @@ private: int message_buffer_is_empty(); - bool message_buffer_write(void *ptr, int size); + bool message_buffer_write(const void *ptr, int size); int message_buffer_get_ptr(void **ptr, bool *is_part); void message_buffer_mark_read(int n); - void pass_message(mavlink_message_t *msg); + void pass_message(const mavlink_message_t *msg); static int mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg); @@ -378,5 +323,4 @@ private: * Main mavlink task. */ int task_main(int argc, char *argv[]); - }; diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp new file mode 100644 index 000000000..1eab7d761 --- /dev/null +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -0,0 +1,823 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mavlink_mission.cpp + * MAVLink mission manager implementation. + * + * @author Lorenz Meier + * @author Julian Oes + * @author Anton Babushkin + */ + +#include "mavlink_mission.h" +#include "mavlink_main.h" + +#include +#include +#include +#include + +#include +#include +#include + +/* oddly, ERROR is not defined for c++ */ +#ifdef ERROR +# undef ERROR +#endif +static const int ERROR = -1; + + +MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : + _mavlink(mavlink), + _channel(mavlink->get_channel()), + _comp_id(MAV_COMP_ID_MISSIONPLANNER), + _state(MAVLINK_WPM_STATE_IDLE), + _time_last_recv(0), + _time_last_sent(0), + _action_timeout(MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT), + _retry_timeout(MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT), + _max_count(DM_KEY_WAYPOINTS_OFFBOARD_0_MAX), + _count(0), + _current_seq(0), + _dataman_id(0), + _transfer_dataman_id(0), + _transfer_count(0), + _transfer_seq(0), + _transfer_current_seq(0), + _transfer_partner_sysid(0), + _transfer_partner_compid(0), + _offboard_mission_sub(-1), + _mission_result_sub(-1), + _offboard_mission_pub(-1), + _slow_rate_limiter(2000000.0f / mavlink->get_rate_mult()), + _verbose(false) +{ + _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission)); + _mission_result_sub = orb_subscribe(ORB_ID(mission_result)); + + init_offboard_mission(); +} + +MavlinkMissionManager::~MavlinkMissionManager() +{ + close(_offboard_mission_pub); + close(_mission_result_sub); +} + +void +MavlinkMissionManager::init_offboard_mission() +{ + mission_s mission_state; + if (dm_read(DM_KEY_MISSION_STATE, 0, &mission_state, sizeof(mission_s)) == sizeof(mission_s)) { + _dataman_id = mission_state.dataman_id; + _count = mission_state.count; + _current_seq = mission_state.current_seq; + + warnx("offboard mission init: dataman_id=%d, count=%u, current_seq=%d", _dataman_id, _count, _current_seq); + + } else { + _dataman_id = 0; + _count = 0; + _current_seq = 0; + warnx("offboard mission init: ERROR, reading mission state failed"); + } +} + +/** + * Write new mission state to dataman and publish offboard_mission topic to notify navigator about changes. + */ +int +MavlinkMissionManager::update_active_mission(int dataman_id, unsigned count, int seq) +{ + struct mission_s mission; + + mission.dataman_id = dataman_id; + mission.count = count; + mission.current_seq = seq; + + /* update mission state in dataman */ + /* lock MISSION_STATE item */ + dm_lock(DM_KEY_MISSION_STATE); + + int res = dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission, sizeof(mission_s)); + + /* unlock MISSION_STATE item */ + dm_unlock(DM_KEY_MISSION_STATE); + + if (res == sizeof(mission_s)) { + /* update active mission state */ + _dataman_id = dataman_id; + _count = count; + _current_seq = seq; + + /* mission state saved successfully, publish offboard_mission topic */ + if (_offboard_mission_pub < 0) { + _offboard_mission_pub = orb_advertise(ORB_ID(offboard_mission), &mission); + + } else { + orb_publish(ORB_ID(offboard_mission), _offboard_mission_pub, &mission); + } + + return OK; + + } else { + warnx("ERROR: can't save mission state"); + _mavlink->send_statustext(MAV_SEVERITY_CRITICAL, "ERROR: can't save mission state"); + + return ERROR; + } +} + +void +MavlinkMissionManager::send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type) +{ + mavlink_message_t msg; + mavlink_mission_ack_t wpa; + + wpa.target_system = sysid; + wpa.target_component = compid; + wpa.type = type; + + mavlink_msg_mission_ack_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpa); + _mavlink->send_message(&msg); + + if (_verbose) { warnx("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system); } +} + + +void +MavlinkMissionManager::send_mission_current(uint16_t seq) +{ + if (seq < _count) { + mavlink_message_t msg; + mavlink_mission_current_t wpc; + + wpc.seq = seq; + + mavlink_msg_mission_current_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpc); + _mavlink->send_message(&msg); + + } else if (seq == 0 && _count == 0) { + /* don't broadcast if no WPs */ + + } else { + if (_verbose) { warnx("WPM: Send MISSION_CURRENT ERROR: seq %u out of bounds", seq); } + + _mavlink->send_statustext("ERROR: wp index out of bounds"); + } +} + + +void +MavlinkMissionManager::send_mission_count(uint8_t sysid, uint8_t compid, uint16_t count) +{ + _time_last_sent = hrt_absolute_time(); + + mavlink_message_t msg; + mavlink_mission_count_t wpc; + + wpc.target_system = sysid; + wpc.target_component = compid; + wpc.count = _count; + + mavlink_msg_mission_count_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpc); + _mavlink->send_message(&msg); + + if (_verbose) { warnx("WPM: Send MISSION_COUNT %u to ID %u", wpc.count, wpc.target_system); } +} + + +void +MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq) +{ + dm_item_t dm_item = _dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; + struct mission_item_s mission_item; + + if (dm_read(dm_item, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { + _time_last_sent = hrt_absolute_time(); + + /* create mission_item_s from mavlink_mission_item_t */ + mavlink_mission_item_t wp; + format_mavlink_mission_item(&mission_item, &wp); + + mavlink_message_t msg; + wp.target_system = sysid; + wp.target_component = compid; + wp.seq = seq; + wp.current = (_current_seq == seq) ? 1 : 0; + mavlink_msg_mission_item_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wp); + _mavlink->send_message(&msg); + + if (_verbose) { warnx("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system); } + + } else { + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); + _mavlink->send_statustext("#audio: Unable to read from micro SD"); + + if (_verbose) { warnx("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id); } + } +} + + +void +MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint16_t seq) +{ + if (seq < _max_count) { + _time_last_sent = hrt_absolute_time(); + + mavlink_message_t msg; + mavlink_mission_request_t wpr; + wpr.target_system = sysid; + wpr.target_component = compid; + wpr.seq = seq; + mavlink_msg_mission_request_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpr); + _mavlink->send_message(&msg); + + if (_verbose) { warnx("WPM: Send MISSION_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system); } + + } else { + _mavlink->send_statustext("ERROR: Waypoint index exceeds list capacity"); + + if (_verbose) { warnx("WPM: Send MISSION_REQUEST ERROR: seq %u exceeds list capacity", seq); } + } +} + + +void +MavlinkMissionManager::send_mission_item_reached(uint16_t seq) +{ + mavlink_message_t msg; + mavlink_mission_item_reached_t wp_reached; + + wp_reached.seq = seq; + + mavlink_msg_mission_item_reached_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wp_reached); + _mavlink->send_message(&msg); + + if (_verbose) { warnx("WPM: Send MISSION_ITEM_REACHED reached_seq %u", wp_reached.seq); } +} + + +void +MavlinkMissionManager::eventloop() +{ + hrt_abstime now = hrt_absolute_time(); + + bool updated = false; + orb_check(_mission_result_sub, &updated); + + if (updated) { + mission_result_s mission_result; + orb_copy(ORB_ID(mission_result), _mission_result_sub, &mission_result); + + _current_seq = mission_result.seq_current; + + if (_verbose) { warnx("WPM: got mission result, new current_seq: %d", _current_seq); } + + if (mission_result.reached) { + send_mission_item_reached((uint16_t)mission_result.seq_reached); + } + + send_mission_current(_current_seq); + + } else { + if (_slow_rate_limiter.check(now)) { + send_mission_current(_current_seq); + } + } + + /* check for timed-out operations */ + if (_state != MAVLINK_WPM_STATE_IDLE && hrt_elapsed_time(&_time_last_recv) > _action_timeout) { + _mavlink->send_statustext("Operation timeout"); + + if (_verbose) { warnx("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state); } + + _state = MAVLINK_WPM_STATE_IDLE; + + } else if (_state == MAVLINK_WPM_STATE_GETLIST && hrt_elapsed_time(&_time_last_sent) > _retry_timeout) { + /* try to request item again after timeout */ + send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq); + + } else if (_state == MAVLINK_WPM_STATE_SENDLIST && hrt_elapsed_time(&_time_last_sent) > _retry_timeout) { + if (_transfer_seq == 0) { + /* try to send items count again after timeout */ + send_mission_count(_transfer_partner_sysid, _transfer_partner_compid, _transfer_count); + + } else { + /* try to send item again after timeout */ + send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq - 1); + } + } +} + + +void +MavlinkMissionManager::handle_message(const mavlink_message_t *msg) +{ + switch (msg->msgid) { + case MAVLINK_MSG_ID_MISSION_ACK: + handle_mission_ack(msg); + break; + + case MAVLINK_MSG_ID_MISSION_SET_CURRENT: + handle_mission_set_current(msg); + break; + + case MAVLINK_MSG_ID_MISSION_REQUEST_LIST: + handle_mission_request_list(msg); + break; + + case MAVLINK_MSG_ID_MISSION_REQUEST: + handle_mission_request(msg); + break; + + case MAVLINK_MSG_ID_MISSION_COUNT: + handle_mission_count(msg); + break; + + case MAVLINK_MSG_ID_MISSION_ITEM: + handle_mission_item(msg); + break; + + case MAVLINK_MSG_ID_MISSION_CLEAR_ALL: + handle_mission_clear_all(msg); + break; + + default: + break; + } +} + + +void +MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg) +{ + mavlink_mission_ack_t wpa; + mavlink_msg_mission_ack_decode(msg, &wpa); + + if (wpa.target_system == mavlink_system.sysid /*&& wpa.target_component == mavlink_wpm_comp_id*/) { + if ((msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid)) { + if (_state == MAVLINK_WPM_STATE_SENDLIST) { + _time_last_recv = hrt_absolute_time(); + + if (_transfer_seq == _count) { + if (_verbose) { warnx("WPM: MISSION_ACK OK all items sent, switch to state IDLE"); } + + } else { + if (_verbose) { warnx("WPM: MISSION_ACK ERROR: not all items sent, switch to state IDLE anyway"); } + } + + _state = MAVLINK_WPM_STATE_IDLE; + } + + } else { + _mavlink->send_statustext("REJ. WP CMD: partner id mismatch"); + + if (_verbose) { warnx("WPM: MISSION_ACK ERROR: rejected, partner ID mismatch"); } + } + } +} + + +void +MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg) +{ + mavlink_mission_set_current_t wpc; + mavlink_msg_mission_set_current_decode(msg, &wpc); + + if (wpc.target_system == mavlink_system.sysid /*&& wpc.target_component == mavlink_wpm_comp_id*/) { + if (_state == MAVLINK_WPM_STATE_IDLE) { + _time_last_recv = hrt_absolute_time(); + + if (wpc.seq < _count) { + if (update_active_mission(_dataman_id, _count, wpc.seq) == OK) { + if (_verbose) { warnx("WPM: MISSION_SET_CURRENT seq=%d OK", wpc.seq); } + + } else { + if (_verbose) { warnx("WPM: MISSION_SET_CURRENT seq=%d ERROR", wpc.seq); } + } + + } else { + if (_verbose) { warnx("WPM: MISSION_SET_CURRENT seq=%d ERROR: not in list", wpc.seq); } + + _mavlink->send_statustext("IGN WP CURR CMD: Not in list"); + } + + } else { + if (_verbose) { warnx("WPM: MISSION_SET_CURRENT ERROR: busy"); } + + _mavlink->send_statustext("IGN WP CURR CMD: Busy"); + } + } +} + + +void +MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg) +{ + mavlink_mission_request_list_t wprl; + mavlink_msg_mission_request_list_decode(msg, &wprl); + + if (wprl.target_system == mavlink_system.sysid /*&& wprl.target_component == mavlink_wpm_comp_id*/) { + if (_state == MAVLINK_WPM_STATE_IDLE || _state == MAVLINK_WPM_STATE_SENDLIST) { + _time_last_recv = hrt_absolute_time(); + + if (_count > 0) { + _state = MAVLINK_WPM_STATE_SENDLIST; + _transfer_seq = 0; + _transfer_count = _count; + _transfer_partner_sysid = msg->sysid; + _transfer_partner_compid = msg->compid; + + if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST OK, %u mission items to send", _transfer_count); } + + } else { + if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST OK nothing to send, mission is empty"); } + } + + send_mission_count(msg->sysid, msg->compid, _count); + + } else { + if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST ERROR: busy"); } + + _mavlink->send_statustext("IGN REQUEST LIST: Busy"); + } + } +} + + +void +MavlinkMissionManager::handle_mission_request(const mavlink_message_t *msg) +{ + mavlink_mission_request_t wpr; + mavlink_msg_mission_request_decode(msg, &wpr); + + if (wpr.target_system == mavlink_system.sysid /*&& wpr.target_component == mavlink_wpm_comp_id*/) { + if (msg->sysid == _transfer_partner_sysid && msg->compid == _transfer_partner_compid) { + if (_state == MAVLINK_WPM_STATE_SENDLIST) { + _time_last_recv = hrt_absolute_time(); + + /* _transfer_seq contains sequence of expected request */ + if (wpr.seq == _transfer_seq && _transfer_seq < _transfer_count) { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u from ID %u", wpr.seq, msg->sysid); } + + _transfer_seq++; + + } else if (wpr.seq == _transfer_seq - 1 && wpr.seq >= 0) { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u from ID %u (again)", wpr.seq, msg->sysid); } + + } else { + if (_transfer_seq > 0 && _transfer_seq < _transfer_count) { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u from ID %u unexpected, must be %i or %i", wpr.seq, msg->sysid, _transfer_seq - 1, _transfer_seq); } + + } else if (_transfer_seq <= 0) { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid, _transfer_seq); } + + } else { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u from ID %u unexpected, must be %i", wpr.seq, msg->sysid, _transfer_seq - 1); } + } + + _state = MAVLINK_WPM_STATE_IDLE; + + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); + _mavlink->send_statustext("REJ. WP CMD: Req. WP was unexpected"); + return; + } + + /* double check bounds in case of items count changed */ + if (wpr.seq >= 0 && wpr.seq < _count) { + send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, wpr.seq); + + } else { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u out of bound [0, %u]", wpr.seq, msg->sysid, wpr.seq, _count - 1); } + + _state = MAVLINK_WPM_STATE_IDLE; + + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); + _mavlink->send_statustext("REJ. WP CMD: Req. WP was unexpected"); + } + + } else if (_state == MAVLINK_WPM_STATE_IDLE) { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: no transfer"); } + + _mavlink->send_statustext("IGN MISSION_ITEM_REQUEST: No transfer"); + + } else { + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: busy (state %d).", _state); } + + _mavlink->send_statustext("REJ. WP CMD: Busy"); + } + + } else { + _mavlink->send_statustext("REJ. WP CMD: partner id mismatch"); + + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: rejected, partner ID mismatch"); } + } + } +} + + +void +MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) +{ + mavlink_mission_count_t wpc; + mavlink_msg_mission_count_decode(msg, &wpc); + + if (wpc.target_system == mavlink_system.sysid/* && wpc.target_component == mavlink_wpm_comp_id*/) { + if (_state == MAVLINK_WPM_STATE_IDLE) { + _time_last_recv = hrt_absolute_time(); + + if (wpc.count > _max_count) { + if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: too many waypoints (%d), supported: %d", wpc.count, _max_count); } + + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_NO_SPACE); + return; + } + + if (wpc.count == 0) { + if (_verbose) { warnx("WPM: MISSION_COUNT 0, clearing waypoints list and staying in state MAVLINK_WPM_STATE_IDLE"); } + + /* alternate dataman ID anyway to let navigator know about changes */ + update_active_mission(_dataman_id == 0 ? 1 : 0, 0, 0); + _mavlink->send_statustext("WP COUNT 0: CLEAR MISSION"); + + // TODO send ACK? + return; + } + + if (_verbose) { warnx("WPM: MISSION_COUNT %u from ID %u, changing state to MAVLINK_WPM_STATE_GETLIST", wpc.count, msg->sysid); } + + _state = MAVLINK_WPM_STATE_GETLIST; + _transfer_seq = 0; + _transfer_partner_sysid = msg->sysid; + _transfer_partner_compid = msg->compid; + _transfer_count = wpc.count; + _transfer_dataman_id = _dataman_id == 0 ? 1 : 0; // use inactive storage for transmission + _transfer_current_seq = -1; + + } else if (_state == MAVLINK_WPM_STATE_GETLIST) { + _time_last_recv = hrt_absolute_time(); + + if (_transfer_seq == 0) { + /* looks like our MISSION_REQUEST was lost, try again */ + if (_verbose) { warnx("WPM: MISSION_COUNT %u from ID %u (again)", wpc.count, msg->sysid); } + + _mavlink->send_statustext("WP CMD OK AGAIN"); + + } else { + if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq); } + + _mavlink->send_statustext("REJ. WP CMD: Busy"); + return; + } + + } else { + if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, state %i", _state); } + + _mavlink->send_statustext("IGN MISSION_COUNT: Busy"); + return; + } + + send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq); + } +} + + +void +MavlinkMissionManager::handle_mission_item(const mavlink_message_t *msg) +{ + mavlink_mission_item_t wp; + mavlink_msg_mission_item_decode(msg, &wp); + + if (wp.target_system == mavlink_system.sysid && wp.target_component == _comp_id) { + if (_state == MAVLINK_WPM_STATE_GETLIST) { + _time_last_recv = hrt_absolute_time(); + + if (wp.seq != _transfer_seq) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u was not the expected %u", wp.seq, _transfer_seq); } + + /* don't send request here, it will be performed in eventloop after timeout */ + return; + } + + } else if (_state == MAVLINK_WPM_STATE_IDLE) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: no transfer"); } + + _mavlink->send_statustext("IGN MISSION_ITEM: No transfer"); + return; + + } else { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: busy, state %i", _state); } + + _mavlink->send_statustext("IGN MISSION_ITEM: Busy"); + return; + } + + struct mission_item_s mission_item; + int ret = parse_mavlink_mission_item(&wp, &mission_item); + + if (ret != OK) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq); } + + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, ret); + _state = MAVLINK_WPM_STATE_IDLE; + return; + } + + dm_item_t dm_item = _transfer_dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; + + if (dm_write(dm_item, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, sizeof(struct mission_item_s)) != sizeof(struct mission_item_s)) { + if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _transfer_dataman_id); } + + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); + _mavlink->send_statustext("#audio: Unable to write on micro SD"); + _state = MAVLINK_WPM_STATE_IDLE; + return; + } + + /* waypoint marked as current */ + if (wp.current) { + _transfer_current_seq = wp.seq; + } + + if (_verbose) { warnx("WPM: MISSION_ITEM seq %u received", wp.seq); } + + _transfer_seq = wp.seq + 1; + + if (_transfer_seq == _transfer_count) { + /* got all new mission items successfully */ + if (_verbose) { warnx("WPM: MISSION_ITEM got all %u items, current_seq=%u, changing state to MAVLINK_WPM_STATE_IDLE", _transfer_count, _transfer_current_seq); } + + _state = MAVLINK_WPM_STATE_IDLE; + + if (update_active_mission(_transfer_dataman_id, _transfer_count, _transfer_current_seq) == OK) { + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ACCEPTED); + + } else { + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); + } + + } else { + /* request next item */ + send_mission_request(_transfer_partner_sysid, _transfer_partner_compid, _transfer_seq); + } + } +} + + +void +MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg) +{ + mavlink_mission_clear_all_t wpca; + mavlink_msg_mission_clear_all_decode(msg, &wpca); + + if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */) { + + if (_state == MAVLINK_WPM_STATE_IDLE) { + /* don't touch mission items storage itself, but only items count in mission state */ + _time_last_recv = hrt_absolute_time(); + + if (update_active_mission(_dataman_id == 0 ? 1 : 0, 0, 0) == OK) { + if (_verbose) { warnx("WPM: CLEAR_ALL OK"); } + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ACCEPTED); + + } else { + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); + } + + } else { + _mavlink->send_statustext("IGN WP CLEAR CMD: Busy"); + + if (_verbose) { warnx("WPM: CLEAR_ALL IGNORED: busy"); } + } + } +} + +int +MavlinkMissionManager::parse_mavlink_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item) +{ + /* only support global waypoints for now */ + switch (mavlink_mission_item->frame) { + case MAV_FRAME_GLOBAL: + mission_item->lat = (double)mavlink_mission_item->x; + mission_item->lon = (double)mavlink_mission_item->y; + mission_item->altitude = mavlink_mission_item->z; + mission_item->altitude_is_relative = false; + break; + + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + mission_item->lat = (double)mavlink_mission_item->x; + mission_item->lon = (double)mavlink_mission_item->y; + mission_item->altitude = mavlink_mission_item->z; + mission_item->altitude_is_relative = true; + break; + + case MAV_FRAME_LOCAL_NED: + case MAV_FRAME_LOCAL_ENU: + return MAV_MISSION_UNSUPPORTED_FRAME; + + case MAV_FRAME_MISSION: + default: + return MAV_MISSION_ERROR; + } + + switch (mavlink_mission_item->command) { + case MAV_CMD_NAV_TAKEOFF: + mission_item->pitch_min = mavlink_mission_item->param1; + break; + case MAV_CMD_DO_JUMP: + mission_item->do_jump_mission_index = mavlink_mission_item->param1; + mission_item->do_jump_repeat_count = mavlink_mission_item->param2; + break; + default: + mission_item->acceptance_radius = mavlink_mission_item->param2; + mission_item->time_inside = mavlink_mission_item->param1; + break; + } + + mission_item->yaw = _wrap_pi(mavlink_mission_item->param4 * M_DEG_TO_RAD_F); + mission_item->loiter_radius = fabsf(mavlink_mission_item->param3); + mission_item->loiter_direction = (mavlink_mission_item->param3 > 0) ? 1 : -1; /* 1 if positive CW, -1 if negative CCW */ + mission_item->nav_cmd = (NAV_CMD)mavlink_mission_item->command; + + mission_item->autocontinue = mavlink_mission_item->autocontinue; + // mission_item->index = mavlink_mission_item->seq; + mission_item->origin = ORIGIN_MAVLINK; + + /* reset DO_JUMP count */ + mission_item->do_jump_current_count = 0; + + return MAV_MISSION_ACCEPTED; +} + + +int +MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item) +{ + if (mission_item->altitude_is_relative) { + mavlink_mission_item->frame = MAV_FRAME_GLOBAL; + + } else { + mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT; + } + + switch (mission_item->nav_cmd) { + case NAV_CMD_TAKEOFF: + mavlink_mission_item->param1 = mission_item->pitch_min; + break; + + case NAV_CMD_DO_JUMP: + mavlink_mission_item->param1 = mission_item->do_jump_mission_index; + mavlink_mission_item->param2 = mission_item->do_jump_repeat_count; + break; + + default: + mavlink_mission_item->param2 = mission_item->acceptance_radius; + mavlink_mission_item->param1 = mission_item->time_inside; + break; + } + + mavlink_mission_item->x = (float)mission_item->lat; + mavlink_mission_item->y = (float)mission_item->lon; + mavlink_mission_item->z = mission_item->altitude; + + mavlink_mission_item->param4 = mission_item->yaw * M_RAD_TO_DEG_F; + mavlink_mission_item->param3 = mission_item->loiter_radius * (float)mission_item->loiter_direction; + mavlink_mission_item->command = mission_item->nav_cmd; + mavlink_mission_item->autocontinue = mission_item->autocontinue; + // mavlink_mission_item->seq = mission_item->index; + + return OK; +} diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h new file mode 100644 index 000000000..d8695cf83 --- /dev/null +++ b/src/modules/mavlink/mavlink_mission.h @@ -0,0 +1,176 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mavlink_mission.h + * MAVLink mission manager interface definition. + * + * @author Lorenz Meier + * @author Julian Oes + * @author Anton Babushkin + */ + +#pragma once + +#include "mavlink_bridge_header.h" +#include "mavlink_rate_limiter.h" +#include + +// FIXME XXX - TO BE MOVED TO XML +enum MAVLINK_WPM_STATES { + MAVLINK_WPM_STATE_IDLE = 0, + MAVLINK_WPM_STATE_SENDLIST, + MAVLINK_WPM_STATE_GETLIST, + MAVLINK_WPM_STATE_ENUM_END +}; + +enum MAVLINK_WPM_CODES { + MAVLINK_WPM_CODE_OK = 0, + MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED, + MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED, + MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS, + MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED, + MAVLINK_WPM_CODE_ENUM_END +}; + +#define MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication action timeout in useconds +#define MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT 500000 ///< Protocol communication retry timeout in useconds + +class Mavlink; + +class MavlinkMissionManager { +public: + MavlinkMissionManager(Mavlink *parent); + + ~MavlinkMissionManager(); + + void init_offboard_mission(); + + int update_active_mission(int dataman_id, unsigned count, int seq); + + void send_message(mavlink_message_t *msg); + + /** + * @brief Sends an waypoint ack message + */ + void send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type); + + /** + * @brief Broadcasts the new target waypoint and directs the MAV to fly there + * + * This function broadcasts its new active waypoint sequence number and + * 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. + */ + void send_mission_current(uint16_t seq); + + void send_mission_count(uint8_t sysid, uint8_t compid, uint16_t count); + + void send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq); + + void send_mission_request(uint8_t sysid, uint8_t compid, uint16_t seq); + + /** + * @brief emits a message that a waypoint reached + * + * This function broadcasts a message that a waypoint is reached. + * + * @param seq The waypoint sequence number the MAV has reached. + */ + void send_mission_item_reached(uint16_t seq); + + void eventloop(); + + void handle_message(const mavlink_message_t *msg); + + void handle_mission_ack(const mavlink_message_t *msg); + + void handle_mission_set_current(const mavlink_message_t *msg); + + void handle_mission_request_list(const mavlink_message_t *msg); + + void handle_mission_request(const mavlink_message_t *msg); + + void handle_mission_count(const mavlink_message_t *msg); + + void handle_mission_item(const mavlink_message_t *msg); + + void handle_mission_clear_all(const mavlink_message_t *msg); + + /** + * Parse mavlink MISSION_ITEM message to get mission_item_s. + */ + int parse_mavlink_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item); + + /** + * Format mission_item_s as mavlink MISSION_ITEM message. + */ + int format_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item); + + void set_verbose(bool v) { _verbose = v; } + +private: + Mavlink* _mavlink; + mavlink_channel_t _channel; + uint8_t _comp_id; + + enum MAVLINK_WPM_STATES _state; ///< Current state + + uint64_t _time_last_recv; + uint64_t _time_last_sent; + + uint32_t _action_timeout; + uint32_t _retry_timeout; + unsigned _max_count; ///< Maximal count of mission items + + int _dataman_id; ///< Dataman storage ID for active mission + unsigned _count; ///< Count of items in active mission + int _current_seq; ///< Current item sequence in active mission + + int _transfer_dataman_id; ///< Dataman storage ID for current transmission + unsigned _transfer_count; ///< Items count in current transmission + int _transfer_seq; ///< Item sequence in current transmission + int _transfer_current_seq; ///< Current item ID for current transmission (-1 means not initialized) + uint8_t _transfer_partner_sysid; ///< Partener SysID for current transmission + uint8_t _transfer_partner_compid; ///< Partner ComponentID for current transmission + + int _offboard_mission_sub; + int _mission_result_sub; + orb_advert_t _offboard_mission_pub; + + MavlinkRateLimiter _slow_rate_limiter; + + bool _verbose; +}; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 1e217ec70..834852d6f 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -79,7 +79,6 @@ __BEGIN_DECLS #include "mavlink_bridge_header.h" #include "mavlink_receiver.h" #include "mavlink_main.h" -#include "util.h" __END_DECLS @@ -902,16 +901,8 @@ MavlinkReceiver::receive_thread(void *arg) /* handle generic messages and commands */ handle_message(&msg); - /* handle packet with waypoint component */ - _mavlink->mavlink_wpm_message_handler(&msg); - - /* handle packet with parameter component */ - _mavlink->mavlink_pm_message_handler(_mavlink->get_channel(), &msg); - - if (_mavlink->get_forwarding_on()) { - /* forward any messages to other mavlink instances */ - Mavlink::forward_message(&msg, _mavlink); - } + /* handle packet with parent object */ + _mavlink->handle_message(&msg); } } } diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index 9ab84b58a..df5d037f8 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -100,8 +100,6 @@ public: static void *start_helper(void *context); private: - perf_counter_t _loop_perf; /**< loop performance counter */ - Mavlink *_mavlink; void handle_message(mavlink_message_t *msg); diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk index f532e26fe..725a9e184 100644 --- a/src/modules/mavlink/module.mk +++ b/src/modules/mavlink/module.mk @@ -39,6 +39,7 @@ MODULE_COMMAND = mavlink SRCS += mavlink_main.cpp \ mavlink.c \ mavlink_receiver.cpp \ + mavlink_mission.cpp \ mavlink_orb_subscription.cpp \ mavlink_messages.cpp \ mavlink_stream.cpp \ diff --git a/src/modules/mavlink/util.h b/src/modules/mavlink/util.h deleted file mode 100644 index 5ca9a085d..000000000 --- a/src/modules/mavlink/util.h +++ /dev/null @@ -1,53 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file util.h - * Utility and helper functions and data. - */ - -#pragma once - -/** MAVLink communications channel */ -extern uint8_t chan; - -/** Shutdown marker */ -extern volatile bool thread_should_exit; - -/** Waypoint storage */ -extern mavlink_wpm_storage *wpm; - -/** - * Translate the custom state into standard mavlink modes and state. - */ -extern void get_mavlink_mode_and_state(uint8_t *mavlink_state, uint8_t *mavlink_base_mode, uint32_t *mavlink_custom_mode); diff --git a/src/modules/mavlink/waypoints.h b/src/modules/mavlink/waypoints.h deleted file mode 100644 index a2109f2d8..000000000 --- a/src/modules/mavlink/waypoints.h +++ /dev/null @@ -1,111 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2009-2014 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file waypoints.h - * MAVLink waypoint protocol definition (BSD-relicensed). - * - * @author Petri Tanskanen - * @author Lorenz Meier - * @author Thomas Gubler - * @author Julian Oes - */ - -#ifndef WAYPOINTS_H_ -#define WAYPOINTS_H_ - -/* This assumes you have the mavlink headers on your include path - or in the same folder as this source file */ - -#include -#include "mavlink_bridge_header.h" -#include -#include - -enum MAVLINK_WPM_STATES { - MAVLINK_WPM_STATE_IDLE = 0, - MAVLINK_WPM_STATE_SENDLIST, - MAVLINK_WPM_STATE_SENDLIST_SENDWPS, - MAVLINK_WPM_STATE_GETLIST, - MAVLINK_WPM_STATE_GETLIST_GETWPS, - MAVLINK_WPM_STATE_GETLIST_GOTALL, - MAVLINK_WPM_STATE_ENUM_END -}; - -enum MAVLINK_WPM_CODES { - MAVLINK_WPM_CODE_OK = 0, - MAVLINK_WPM_CODE_ERR_WAYPOINT_ACTION_NOT_SUPPORTED, - MAVLINK_WPM_CODE_ERR_WAYPOINT_FRAME_NOT_SUPPORTED, - MAVLINK_WPM_CODE_ERR_WAYPOINT_OUT_OF_BOUNDS, - MAVLINK_WPM_CODE_ERR_WAYPOINT_MAX_NUMBER_EXCEEDED, - MAVLINK_WPM_CODE_ENUM_END -}; - - -#define MAVLINK_WPM_MAX_WP_COUNT 255 -#define MAVLINK_WPM_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication timeout in useconds -#define MAVLINK_WPM_SETPOINT_DELAY_DEFAULT 1000000 ///< When to send a new setpoint -#define MAVLINK_WPM_PROTOCOL_DELAY_DEFAULT 40000 - - -struct mavlink_wpm_storage { - uint16_t size; - uint16_t max_size; - enum MAVLINK_WPM_STATES current_state; - int16_t current_wp_id; ///< Waypoint in current transmission - uint16_t current_count; - uint8_t current_partner_sysid; - uint8_t current_partner_compid; - uint64_t timestamp_lastaction; - uint64_t timestamp_last_send_setpoint; - uint32_t action_timeout; - int current_dataman_id; -}; - -typedef struct mavlink_wpm_storage mavlink_wpm_storage; - -int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item); -int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item); - - -void mavlink_wpm_init(mavlink_wpm_storage *state); -void mavlink_waypoint_eventloop(uint64_t now); -void mavlink_wpm_message_handler(const mavlink_message_t *msg); - -extern void mavlink_missionlib_current_waypoint_changed(uint16_t index, float param1, - float param2, float param3, float param4, float param5_lat_x, - float param6_lon_y, float param7_alt_z, uint8_t frame, uint16_t command); - -static uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN]; - -#endif /* WAYPOINTS_H_ */ diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index d9d8353f6..f6d304c37 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -67,13 +67,11 @@ Mission::Mission(Navigator *navigator, const char *name) : _current_offboard_mission_index(-1), _mission_result_pub(-1), _mission_result({0}), - _mission_type(MISSION_TYPE_NONE) + _mission_type(MISSION_TYPE_NONE), + _inited(false) { /* load initial params */ updateParams(); - /* set initial mission items */ - on_inactive(); - } Mission::~Mission() @@ -85,16 +83,25 @@ Mission::on_inactive() { _first_run = true; - /* check anyway if missions have changed so that feedback to groundstation is given */ - bool onboard_updated; - orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated); - if (onboard_updated) { - update_onboard_mission(); - } + if (_inited) { + /* check if missions have changed so that feedback to ground station is given */ + bool onboard_updated = false; + orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated); + if (onboard_updated) { + update_onboard_mission(); + } - bool offboard_updated; - orb_check(_navigator->get_offboard_mission_sub(), &offboard_updated); - if (offboard_updated) { + bool offboard_updated = false; + orb_check(_navigator->get_offboard_mission_sub(), &offboard_updated); + if (offboard_updated) { + update_offboard_mission(); + } + + } else { + /* read mission topics on initialization */ + _inited = true; + + update_onboard_mission(); update_offboard_mission(); } } @@ -105,13 +112,13 @@ Mission::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) bool updated = false; /* check if anything has changed */ - bool onboard_updated; + bool onboard_updated = false; orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated); if (onboard_updated) { update_onboard_mission(); } - bool offboard_updated; + bool offboard_updated = false; orb_check(_navigator->get_offboard_mission_sub(), &offboard_updated); if (offboard_updated) { update_offboard_mission(); @@ -139,9 +146,9 @@ Mission::update_onboard_mission() { if (orb_copy(ORB_ID(onboard_mission), _navigator->get_onboard_mission_sub(), &_onboard_mission) == OK) { /* accept the current index set by the onboard mission if it is within bounds */ - if (_onboard_mission.current_index >=0 - && _onboard_mission.current_index < (int)_onboard_mission.count) { - _current_onboard_mission_index = _onboard_mission.current_index; + if (_onboard_mission.current_seq >=0 + && _onboard_mission.current_seq < (int)_onboard_mission.count) { + _current_onboard_mission_index = _onboard_mission.current_seq; } else { /* if less WPs available, reset to first WP */ if (_current_onboard_mission_index >= (int)_onboard_mission.count) { @@ -154,7 +161,7 @@ Mission::update_onboard_mission() } } else { _onboard_mission.count = 0; - _onboard_mission.current_index = 0; + _onboard_mission.current_seq = 0; _current_onboard_mission_index = 0; } } @@ -163,13 +170,12 @@ void Mission::update_offboard_mission() { if (orb_copy(ORB_ID(offboard_mission), _navigator->get_offboard_mission_sub(), &_offboard_mission) == OK) { - + warnx("offboard mission updated: dataman_id=%d, count=%d, current_seq=%d", _offboard_mission.dataman_id, _offboard_mission.count, _offboard_mission.current_seq); /* determine current index */ - if (_offboard_mission.current_index >= 0 - && _offboard_mission.current_index < (int)_offboard_mission.count) { - _current_offboard_mission_index = _offboard_mission.current_index; + if (_offboard_mission.current_seq >= 0 && _offboard_mission.current_seq < (int)_offboard_mission.count) { + _current_offboard_mission_index = _offboard_mission.current_seq; } else { - /* if less WPs available, reset to first WP */ + /* if less items available, reset to first item */ if (_current_offboard_mission_index >= (int)_offboard_mission.count) { _current_offboard_mission_index = 0; /* if not initialized, set it to 0 */ @@ -194,10 +200,12 @@ Mission::update_offboard_mission() _navigator->get_geofence(), _navigator->get_home_position()->alt); } else { + warnx("offboard mission update failed"); _offboard_mission.count = 0; - _offboard_mission.current_index = 0; + _offboard_mission.current_seq = 0; _current_offboard_mission_index = 0; } + report_current_offboard_mission_item(); } @@ -326,10 +334,10 @@ Mission::is_current_offboard_mission_item_set(struct position_setpoint_s *curren void Mission::get_next_onboard_mission_item(struct position_setpoint_s *next_pos_sp) { - int next_temp_mission_index = _onboard_mission.current_index + 1; + int next_temp_mission_index = _onboard_mission.current_seq + 1; /* try if there is a next onboard mission */ - if (_onboard_mission.current_index >= 0 && + if (_onboard_mission.current_seq >= 0 && next_temp_mission_index < (int)_onboard_mission.count) { struct mission_item_s new_mission_item; if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, false, &next_temp_mission_index, &new_mission_item)) { @@ -349,9 +357,9 @@ void Mission::get_next_offboard_mission_item(struct position_setpoint_s *next_pos_sp) { /* try if there is a next offboard mission */ - int next_temp_mission_index = _offboard_mission.current_index + 1; + int next_temp_mission_index = _offboard_mission.current_seq + 1; warnx("next index: %d, count; %d", next_temp_mission_index, _offboard_mission.count); - if (_offboard_mission.current_index >= 0 && + if (_offboard_mission.current_seq >= 0 && next_temp_mission_index < (int)_offboard_mission.count) { dm_item_t dm_current; if (_offboard_mission.dataman_id == 0) { @@ -441,19 +449,31 @@ Mission::save_offboard_mission_state() /* read current state */ int read_res = dm_read(DM_KEY_MISSION_STATE, 0, &mission_state, sizeof(mission_s)); - /* check if state actually changed to save flash write cycles */ - if (read_res != sizeof(mission_s) || mission_state.dataman_id != _offboard_mission.dataman_id || - mission_state.count != _offboard_mission.count || - mission_state.current_index != _current_offboard_mission_index) { + if (read_res == sizeof(mission_s)) { + /* data read successfully, check dataman ID and items count */ + if (mission_state.dataman_id == _offboard_mission.dataman_id && mission_state.count == _offboard_mission.count) { + /* navigator may modify only sequence, write modified state only if it changed */ + if (mission_state.current_seq != _current_offboard_mission_index) { + if (dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission_state, sizeof(mission_s)) != sizeof(mission_s)) { + warnx("ERROR: can't save mission state"); + mavlink_log_critical(_navigator->get_mavlink_fd(), "ERROR: can't save mission state"); + } + } + } + } else { + /* invalid data, this must not happen and indicates error in offboard_mission publisher */ mission_state.dataman_id = _offboard_mission.dataman_id; mission_state.count = _offboard_mission.count; - mission_state.current_index = _current_offboard_mission_index; + mission_state.current_seq = _current_offboard_mission_index; - /* write modifyed state only if changed */ - if (dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission_state, sizeof(mission_s)) != sizeof(mission_s)) { - mavlink_log_critical(_navigator->get_mavlink_fd(), "error saving mission state"); + warnx("ERROR: invalid mission state"); + mavlink_log_critical(_navigator->get_mavlink_fd(), "ERROR: invalid mission state"); + /* write modified state only if changed */ + if (dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission_state, sizeof(mission_s)) != sizeof(mission_s)) { + warnx("ERROR: can't save mission state"); + mavlink_log_critical(_navigator->get_mavlink_fd(), "ERROR: can't save mission state"); } } @@ -465,8 +485,8 @@ void Mission::report_mission_item_reached() { if (_mission_type == MISSION_TYPE_OFFBOARD) { - _mission_result.mission_reached = true; - _mission_result.mission_index_reached = _current_offboard_mission_index; + _mission_result.reached = true; + _mission_result.seq_reached = _current_offboard_mission_index; } publish_mission_result(); } @@ -474,7 +494,8 @@ Mission::report_mission_item_reached() void Mission::report_current_offboard_mission_item() { - _mission_result.index_current_mission = _current_offboard_mission_index; + warnx("current offboard mission index: %d", _current_offboard_mission_index); + _mission_result.seq_current = _current_offboard_mission_index; publish_mission_result(); save_offboard_mission_state(); @@ -483,7 +504,7 @@ Mission::report_current_offboard_mission_item() void Mission::report_mission_finished() { - _mission_result.mission_finished = true; + _mission_result.finished = true; publish_mission_result(); } @@ -500,6 +521,6 @@ Mission::publish_mission_result() _mission_result_pub = orb_advertise(ORB_ID(mission_result), &_mission_result); } /* reset reached bool */ - _mission_result.mission_reached = false; - _mission_result.mission_finished = false; + _mission_result.reached = false; + _mission_result.finished = false; } diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index 98b11bade..1310671b0 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -183,6 +183,8 @@ private: MISSION_TYPE_OFFBOARD } _mission_type; + bool _inited; + MissionFeasibilityChecker missionFeasiblityChecker; /**< class that checks if a mission is feasible */ }; diff --git a/src/modules/uORB/topics/mission.h b/src/modules/uORB/topics/mission.h index 4bcaaaa5a..499b2e1e5 100644 --- a/src/modules/uORB/topics/mission.h +++ b/src/modules/uORB/topics/mission.h @@ -97,11 +97,15 @@ struct mission_item_s { unsigned do_jump_current_count; /**< count how many times the jump has been done */ }; +/** + * This topic used to notify navigator about mission changes, mission itself and new mission state + * must be stored in dataman before publication. + */ struct mission_s { int dataman_id; /**< default 0, there are two offboard storage places in the dataman: 0 or 1 */ unsigned count; /**< count of the missions stored in the dataman */ - int current_index; /**< default -1, start at the one changed latest */ + int current_seq; /**< default -1, start at the one changed latest */ }; /** diff --git a/src/modules/uORB/topics/mission_result.h b/src/modules/uORB/topics/mission_result.h index ad654a9ff..beb797e62 100644 --- a/src/modules/uORB/topics/mission_result.h +++ b/src/modules/uORB/topics/mission_result.h @@ -53,10 +53,10 @@ struct mission_result_s { - bool mission_reached; /**< true if mission has been reached */ - unsigned mission_index_reached; /**< index of the mission which has been reached */ - unsigned index_current_mission; /**< index of the current mission */ - bool mission_finished; /**< true if mission has been completed */ + unsigned seq_reached; /**< Sequence of the mission item which has been reached */ + unsigned seq_current; /**< Sequence of the current mission item */ + bool reached; /**< true if mission has been reached */ + bool finished; /**< true if mission has been completed */ }; /** -- cgit v1.2.3 From 74ae18c245514d918e6ea58f05de98b9fe4b63a5 Mon Sep 17 00:00:00 2001 From: Benjamin O'Connell-Armand Date: Sat, 14 Jun 2014 18:46:18 -0400 Subject: Fixed rates flags --- src/modules/commander/commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 2c36b2e6c..7baaf7139 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1834,7 +1834,7 @@ set_control_mode() control_mode.flag_control_velocity_enabled = true; break; case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: - control_mode.flag_control_rates_enabled = false; + control_mode.flag_control_rates_enabled = true; control_mode.flag_control_attitude_enabled = false; control_mode.flag_control_altitude_enabled = true; control_mode.flag_control_climb_rate_enabled = true; -- cgit v1.2.3 From 1b8e72be1b9614bff4e1bdf81ad7f3265754e062 Mon Sep 17 00:00:00 2001 From: Kynos Date: Sun, 15 Jun 2014 17:26:14 +0200 Subject: Merge sAcc & pAcc scaling fix from branch inav_gps_delay --- src/drivers/gps/ubx.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index 1783ae0f7..56e7a8bd7 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -643,8 +643,8 @@ UBX::payload_rx_done(void) UBX_TRACE_RXMSG("Rx NAV-SOL\n"); _gps_position->fix_type = _buf.payload_rx_nav_sol.gpsFix; - _gps_position->s_variance_m_s = _buf.payload_rx_nav_sol.sAcc; - _gps_position->p_variance_m = _buf.payload_rx_nav_sol.pAcc; + _gps_position->s_variance_m_s = (float)_buf.payload_rx_nav_sol.sAcc * 1e-2f; // from cm to m + _gps_position->p_variance_m = (float)_buf.payload_rx_nav_sol.pAcc * 1e-2f; // from cm to m _gps_position->satellites_used = _buf.payload_rx_nav_sol.numSV; _gps_position->timestamp_variance = hrt_absolute_time(); -- cgit v1.2.3 From 243db01a37d5d3adecc2e010ac4d9819cf3d6c37 Mon Sep 17 00:00:00 2001 From: Kynos Date: Mon, 16 Jun 2014 01:43:44 +0200 Subject: Request and display MON-VER message at startup --- src/drivers/gps/ubx.cpp | 73 +++++++++++++++++++++++++++++++++++++++++++------ src/drivers/gps/ubx.h | 21 ++++++++++++-- 2 files changed, 84 insertions(+), 10 deletions(-) diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index 56e7a8bd7..be19ce488 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -93,6 +93,8 @@ UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct sate _ack_waiting_msg(0) { decode_init(); + memset(_ubx_sw_version, 0, sizeof(_ubx_sw_version)); + memset(_ubx_hw_version, 0, sizeof(_ubx_hw_version)); } UBX::~UBX() @@ -221,6 +223,9 @@ UBX::configure(unsigned &baudrate) return 1; } + /* request module version information by sending an empty MON-VER message */ + send_message(UBX_MSG_MON_VER, nullptr, 0); + _configured = true; return 0; } @@ -385,10 +390,16 @@ UBX::parse_char(const uint8_t b) case UBX_DECODE_PAYLOAD: UBX_TRACE_PARSER("."); add_byte_to_checksum(b); - if (_rx_msg != UBX_MSG_NAV_SVINFO) { - ret = payload_rx_add(b); // add a payload byte - } else { - ret = payload_rx_add_svinfo(b); // add a svinfo payload byte + switch (_rx_msg) { + case UBX_MSG_NAV_SVINFO: + ret = payload_rx_add_nav_svinfo(b); // add a NAV-SVINFO payload byte + break; + case UBX_MSG_MON_VER: + ret = payload_rx_add_mon_ver(b); // add a MON-VER payload byte + break; + default: + ret = payload_rx_add(b); // add a payload byte + break; } if (ret < 0) { // payload not handled, discard message @@ -477,6 +488,9 @@ UBX::payload_rx_init() _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured break; + case UBX_MSG_MON_VER: + break; // unconditionally handle this message + case UBX_MSG_MON_HW: if ( (_rx_payload_length != sizeof(ubx_payload_rx_mon_hw_ubx6_t)) /* u-blox 6 msg format */ && (_rx_payload_length != sizeof(ubx_payload_rx_mon_hw_ubx7_t))) /* u-blox 7+ msg format */ @@ -559,10 +573,10 @@ UBX::payload_rx_add(const uint8_t b) } /** - * Add svinfo payload rx byte + * Add NAV-SVINFO payload rx byte */ int // -1 = error, 0 = ok, 1 = payload completed -UBX::payload_rx_add_svinfo(const uint8_t b) +UBX::payload_rx_add_nav_svinfo(const uint8_t b) { int ret = 0; @@ -606,6 +620,41 @@ UBX::payload_rx_add_svinfo(const uint8_t b) return ret; } +/** + * Add MON-VER payload rx byte + */ +int // -1 = error, 0 = ok, 1 = payload completed +UBX::payload_rx_add_mon_ver(const uint8_t b) +{ + int ret = 0; + + if (_rx_payload_index < sizeof(ubx_payload_rx_mon_ver_part1_t)) { + // Fill Part 1 buffer + _buf.raw[_rx_payload_index] = b; + } else { + if (_rx_payload_index == sizeof(ubx_payload_rx_mon_ver_part1_t)) { + // Part 1 complete: decode Part 1 buffer + strncpy(_ubx_sw_version, (char*)_buf.payload_rx_mon_ver_part1.swVersion, sizeof(_ubx_sw_version)); + strncpy(_ubx_hw_version, (char*)_buf.payload_rx_mon_ver_part1.hwVersion, sizeof(_ubx_hw_version)); + UBX_WARN("VER sw %30s", _ubx_sw_version); + UBX_WARN("VER hw %10s", _ubx_hw_version); + } + // fill Part 2 buffer + unsigned buf_index = (_rx_payload_index - sizeof(ubx_payload_rx_mon_ver_part1_t)) % sizeof(ubx_payload_rx_mon_ver_part2_t); + _buf.raw[buf_index] = b; + if (buf_index == sizeof(ubx_payload_rx_mon_ver_part2_t) - 1) { + // Part 2 complete: decode Part 2 buffer + UBX_WARN("VER ext %30s", _buf.payload_rx_mon_ver_part2.extension); + } + } + + if (++_rx_payload_index >= _rx_payload_length) { + ret = 1; // payload received completely + } + + return ret; +} + /** * Finish payload rx */ @@ -712,6 +761,12 @@ UBX::payload_rx_done(void) ret = 1; break; + case UBX_MSG_MON_VER: + UBX_TRACE_RXMSG("Rx MON-VER\n"); + + ret = 1; + break; + case UBX_MSG_MON_HW: UBX_TRACE_RXMSG("Rx MON-HW\n"); @@ -813,10 +868,12 @@ UBX::send_message(const uint16_t msg, const uint8_t *payload, const uint16_t len // Calculate checksum calc_checksum(((uint8_t*)&header) + 2, sizeof(header) - 2, &checksum); // skip 2 sync bytes - calc_checksum(payload, length, &checksum); + if (payload != nullptr) + calc_checksum(payload, length, &checksum); // Send message write(_fd, (const void *)&header, sizeof(header)); - write(_fd, (const void *)payload, length); + if (payload != nullptr) + write(_fd, (const void *)payload, length); write(_fd, (const void *)&checksum, sizeof(checksum)); } diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index 8fd8d4da6..c8c89dfad 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -72,6 +72,7 @@ #define UBX_ID_CFG_MSG 0x01 #define UBX_ID_CFG_RATE 0x08 #define UBX_ID_CFG_NAV5 0x24 +#define UBX_ID_MON_VER 0x04 #define UBX_ID_MON_HW 0x09 /* Message Classes & IDs */ @@ -87,6 +88,7 @@ #define UBX_MSG_CFG_RATE ((UBX_CLASS_CFG) | UBX_ID_CFG_RATE << 8) #define UBX_MSG_CFG_NAV5 ((UBX_CLASS_CFG) | UBX_ID_CFG_NAV5 << 8) #define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8) +#define UBX_MSG_MON_VER ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8) /* TX CFG-PRT message contents */ #define UBX_TX_CFG_PRT_PORTID 0x01 /**< UART1 */ @@ -249,6 +251,17 @@ typedef struct { uint32_t pullL; } ubx_payload_rx_mon_hw_ubx7_t; +/* Rx MON-VER Part 1 */ +typedef struct { + uint8_t swVersion[30]; + uint8_t hwVersion[10]; +} ubx_payload_rx_mon_ver_part1_t; + +/* Rx MON-VER Part 2 (repeated) */ +typedef struct { + uint8_t extension[30]; +} ubx_payload_rx_mon_ver_part2_t; + /* Rx ACK-ACK */ typedef union { uint16_t msg; @@ -333,6 +346,8 @@ typedef union { ubx_payload_rx_nav_velned_t payload_rx_nav_velned; ubx_payload_rx_mon_hw_ubx6_t payload_rx_mon_hw_ubx6; ubx_payload_rx_mon_hw_ubx7_t payload_rx_mon_hw_ubx7; + ubx_payload_rx_mon_ver_part1_t payload_rx_mon_ver_part1; + ubx_payload_rx_mon_ver_part2_t payload_rx_mon_ver_part2; ubx_payload_rx_ack_ack_t payload_rx_ack_ack; ubx_payload_rx_ack_nak_t payload_rx_ack_nak; ubx_payload_tx_cfg_prt_t payload_tx_cfg_prt; @@ -366,7 +381,6 @@ typedef enum { UBX_RXMSG_ERROR_LENGTH } ubx_rxmsg_state_t; - /* ACK state */ typedef enum { UBX_ACK_IDLE = 0, @@ -400,7 +414,8 @@ private: * Add payload rx byte */ int payload_rx_add(const uint8_t b); - int payload_rx_add_svinfo(const uint8_t b); + int payload_rx_add_nav_svinfo(const uint8_t b); + int payload_rx_add_mon_ver(const uint8_t b); /** * Finish payload rx @@ -455,6 +470,8 @@ private: hrt_abstime _disable_cmd_last; uint16_t _ack_waiting_msg; ubx_buf_t _buf; + char _ubx_sw_version[30]; + char _ubx_hw_version[10]; }; #endif /* UBX_H_ */ -- cgit v1.2.3 From 0ffb123701c2e6124d7c735cdb55c250564d12c6 Mon Sep 17 00:00:00 2001 From: Kynos Date: Mon, 16 Jun 2014 15:35:38 +0200 Subject: Store hash instead of full strings for SW & HW version --- src/drivers/gps/ubx.cpp | 48 +++++++++++++++++++++++++++++++++++++++--------- src/drivers/gps/ubx.h | 8 ++++++-- 2 files changed, 45 insertions(+), 11 deletions(-) diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index be19ce488..adc7130dd 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -72,6 +72,10 @@ #define MIN(X,Y) ((X) < (Y) ? (X) : (Y)) #define SWAP16(X) ((((X) >> 8) & 0x00ff) | (((X) << 8) & 0xff00)) +#define FNV1_32_INIT ((uint32_t)0x811c9dc5) // init value for FNV1 hash algorithm +#define FNV1_32_PRIME ((uint32_t)0x01000193) // magic prime for FNV1 hash algorithm + + /**** Trace macros, disable for production builds */ #define UBX_TRACE_PARSER(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* decoding progress in parse_char() */ #define UBX_TRACE_RXMSG(s, ...) {/*printf(s, ## __VA_ARGS__);*/} /* Rx msgs in payload_rx_done() */ @@ -90,11 +94,10 @@ UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct sate _got_posllh(false), _got_velned(false), _disable_cmd_last(0), - _ack_waiting_msg(0) + _ack_waiting_msg(0), + _ubx_version(0) { decode_init(); - memset(_ubx_sw_version, 0, sizeof(_ubx_sw_version)); - memset(_ubx_hw_version, 0, sizeof(_ubx_hw_version)); } UBX::~UBX() @@ -633,18 +636,19 @@ UBX::payload_rx_add_mon_ver(const uint8_t b) _buf.raw[_rx_payload_index] = b; } else { if (_rx_payload_index == sizeof(ubx_payload_rx_mon_ver_part1_t)) { - // Part 1 complete: decode Part 1 buffer - strncpy(_ubx_sw_version, (char*)_buf.payload_rx_mon_ver_part1.swVersion, sizeof(_ubx_sw_version)); - strncpy(_ubx_hw_version, (char*)_buf.payload_rx_mon_ver_part1.hwVersion, sizeof(_ubx_hw_version)); - UBX_WARN("VER sw %30s", _ubx_sw_version); - UBX_WARN("VER hw %10s", _ubx_hw_version); + // Part 1 complete: decode Part 1 buffer and calculate hash for SW&HW version strings + _ubx_version = fnv1_32_str(_buf.payload_rx_mon_ver_part1.swVersion, FNV1_32_INIT); + _ubx_version = fnv1_32_str(_buf.payload_rx_mon_ver_part1.hwVersion, _ubx_version); + UBX_WARN("VER hash 0x%08x", _ubx_version); + UBX_WARN("VER hw \"%10s\"", _buf.payload_rx_mon_ver_part1.hwVersion); + UBX_WARN("VER sw \"%30s\"", _buf.payload_rx_mon_ver_part1.swVersion); } // fill Part 2 buffer unsigned buf_index = (_rx_payload_index - sizeof(ubx_payload_rx_mon_ver_part1_t)) % sizeof(ubx_payload_rx_mon_ver_part2_t); _buf.raw[buf_index] = b; if (buf_index == sizeof(ubx_payload_rx_mon_ver_part2_t) - 1) { // Part 2 complete: decode Part 2 buffer - UBX_WARN("VER ext %30s", _buf.payload_rx_mon_ver_part2.extension); + UBX_WARN("VER ext \" %30s\"", _buf.payload_rx_mon_ver_part2.extension); } } @@ -877,3 +881,29 @@ UBX::send_message(const uint16_t msg, const uint8_t *payload, const uint16_t len write(_fd, (const void *)payload, length); write(_fd, (const void *)&checksum, sizeof(checksum)); } + +uint32_t +UBX::fnv1_32_str(uint8_t *str, uint32_t hval) +{ + uint8_t *s = str; + + /* + * FNV-1 hash each octet in the buffer + */ + while (*s) { + + /* multiply by the 32 bit FNV magic prime mod 2^32 */ +#if defined(NO_FNV_GCC_OPTIMIZATION) + hval *= FNV1_32_PRIME; +#else + hval += (hval<<1) + (hval<<4) + (hval<<7) + (hval<<8) + (hval<<24); +#endif + + /* xor the bottom with the current octet */ + hval ^= (uint32_t)*s++; + } + + /* return our new hash value */ + return hval; +} + diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index c8c89dfad..f01b697a3 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -452,6 +452,11 @@ private: */ int wait_for_ack(const uint16_t msg, const unsigned timeout, const bool report); + /** + * Calculate FNV1 hash + */ + uint32_t fnv1_32_str(uint8_t *str, uint32_t hval); + int _fd; struct vehicle_gps_position_s *_gps_position; struct satellite_info_s *_satellite_info; @@ -470,8 +475,7 @@ private: hrt_abstime _disable_cmd_last; uint16_t _ack_waiting_msg; ubx_buf_t _buf; - char _ubx_sw_version[30]; - char _ubx_hw_version[10]; + uint32_t _ubx_version; }; #endif /* UBX_H_ */ -- cgit v1.2.3 From 61833905472465ebab615ecdd567b78eb1628d97 Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Mon, 16 Jun 2014 17:47:10 -0400 Subject: Commander attitude flag fix --- src/modules/commander/commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 7baaf7139..3da43a792 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1835,7 +1835,7 @@ set_control_mode() break; case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: control_mode.flag_control_rates_enabled = true; - control_mode.flag_control_attitude_enabled = false; + control_mode.flag_control_attitude_enabled = true; control_mode.flag_control_altitude_enabled = true; control_mode.flag_control_climb_rate_enabled = true; control_mode.flag_control_position_enabled = true; -- cgit v1.2.3 From e078ef992fc21d86cbd09db89c25332273840b22 Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Tue, 17 Jun 2014 13:21:20 -0400 Subject: Removed publications closing This is an attempt to correct the offboard setpoints being passed on as "NaN" values --- src/modules/mavlink/mavlink_receiver.cpp | 59 ---------------------- src/modules/mc_att_control/mc_att_control_main.cpp | 8 +-- src/modules/mc_pos_control/mc_pos_control_main.cpp | 20 +------- 3 files changed, 3 insertions(+), 84 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index c95ee880c..5528aca5e 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -440,22 +440,6 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message loc_pos_sp.yaw = offboard_control_sp.p3; loc_pos_sp.z = -offboard_control_sp.p4; - /* Close fds to allow position controller to use attitude controller */ - if (_att_sp_pub > 0) { - close(_att_sp_pub); - _att_sp_pub = -1; - } - - if (_rates_sp_pub > 0) { - close(_rates_sp_pub); - _rates_sp_pub = -1; - } - - if (_global_vel_sp_pub > 0) { - close(_global_vel_sp_pub); - _global_vel_sp_pub = -1; - } - if (_local_pos_sp_pub < 0) { _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp_pub); @@ -472,16 +456,6 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message global_vel_sp.vy = offboard_control_sp.p2; global_vel_sp.vz = offboard_control_sp.p3; - if (_att_sp_pub > 0) { - close(_att_sp_pub); - _att_sp_pub = -1; - } - - if (_rates_sp_pub > 0) { - close(_rates_sp_pub); - _rates_sp_pub = -1; - } - if (_global_vel_sp_pub < 0) { _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &_global_vel_sp_pub); @@ -501,12 +475,6 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message att_sp.timestamp = hrt_absolute_time(); - /* Close fd to allow attitude controller to publish its own rates sp*/ - if (_rates_sp_pub > 0) { - close(_rates_sp_pub); - _rates_sp_pub = -1; - } - if (_att_sp_pub < 0) { _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); @@ -1056,33 +1024,6 @@ MavlinkReceiver::receive_thread(void *arg) } } } - /* Close unused fds when not in offboard mode anymore */ - bool updated; - orb_check(_control_mode_sub, &updated); - if (updated) { - orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); - if (!_control_mode.flag_control_offboard_enabled) { - if (_local_pos_sp_pub > 0) { - close(_local_pos_sp_pub); - _local_pos_sp_pub = -1; - } - - if (_global_vel_sp_pub > 0) { - close(_global_vel_sp_pub); - _global_vel_sp_pub = -1; - } - - if (_att_sp_pub > 0) { - close(_att_sp_pub); - _att_sp_pub = -1; - } - - if (_rates_sp_pub > 0) { - close(_rates_sp_pub); - _rates_sp_pub = -1; - } - } - } } return NULL; diff --git a/src/modules/mc_att_control/mc_att_control_main.cpp b/src/modules/mc_att_control/mc_att_control_main.cpp index 26c0c386f..20e016da3 100644 --- a/src/modules/mc_att_control/mc_att_control_main.cpp +++ b/src/modules/mc_att_control/mc_att_control_main.cpp @@ -584,15 +584,9 @@ MulticopterAttitudeControl::control_attitude(float dt) if (_att_sp_pub > 0) { orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &_v_att_sp); - } else if (!_v_control_mode.flag_control_offboard_enabled) { + } else { _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &_v_att_sp); } - - /* Close fd to let offboard att sp be advertised in mavlink receiver*/ - if (_v_control_mode.flag_control_offboard_enabled && _att_sp_pub > 0) { - close(_att_sp_pub); - _att_sp_pub = -1; - } } /* rotation matrix for current state */ diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 35db05499..41fb20108 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -733,15 +733,10 @@ MulticopterPositionControl::task_main() if (_local_pos_sp_pub > 0) { orb_publish(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_pub, &_local_pos_sp); - } else if (!_control_mode.flag_control_offboard_enabled) { + } else { _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp); } - /* Close fd to let offboard pos sp be advertised in mavlink receiver*/ - if (_control_mode.flag_control_offboard_enabled && _local_pos_sp_pub > 0) { - close(_local_pos_sp_pub); - _local_pos_sp_pub = -1; - } if (!_control_mode.flag_control_manual_enabled && _pos_sp_triplet.current.valid && _pos_sp_triplet.current.type == SETPOINT_TYPE_IDLE) { /* idle state, don't run controller and set zero thrust */ @@ -822,16 +817,10 @@ MulticopterPositionControl::task_main() if (_global_vel_sp_pub > 0) { orb_publish(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_pub, &_global_vel_sp); - } else if (!_control_mode.flag_control_offboard_enabled) { + } else { _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &_global_vel_sp); } - /* Close fd to let offboard vel sp be advertised in mavlink receiver */ - if (_control_mode.flag_control_offboard_enabled && _global_vel_sp_pub > 0) { - close(_global_vel_sp_pub); - _global_vel_sp_pub = -1; - } - if (_control_mode.flag_control_climb_rate_enabled || _control_mode.flag_control_velocity_enabled) { /* reset integrals if needed */ if (_control_mode.flag_control_climb_rate_enabled) { @@ -1099,11 +1088,6 @@ MulticopterPositionControl::task_main() reset_int_z = true; reset_int_xy = true; - /* Close att_sp pub to allow offboard mode or att controller to advertise */ - if (_att_sp_pub > 0) { - close(_att_sp_pub); - _att_sp_pub = -1; - } } /* reset altitude controller integral (hovering throttle) to manual throttle after manual throttle control */ -- cgit v1.2.3 From 9d18da4433773cfa02bec1d33fdb34e4d03d1442 Mon Sep 17 00:00:00 2001 From: t0ni0 Date: Wed, 18 Jun 2014 16:45:38 -0400 Subject: Adds NaN checks and setpoint resets for offboard posctl --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 31 ++++++++++++++-------- 1 file changed, 20 insertions(+), 11 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 41fb20108..a4c871d95 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -675,21 +675,30 @@ MulticopterPositionControl::task_main() orb_check(_local_pos_sp_sub, &updated); if (updated) { - orb_copy(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_sub, - &_local_pos_sp); + orb_copy(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_sub, &_local_pos_sp); } - /* Make sure position control is selected i.e. not only velocity control */ - if (_control_mode.flag_control_position_enabled) { - _pos_sp(0) = _local_pos_sp.x; - _pos_sp(1) = _local_pos_sp.y; - } + if (isfinite(_local_pos_sp.x) && isfinite(_local_pos_sp.y) && isfinite(_local_pos_sp.z) && isfinite(_local_pos_sp.yaw)) { + /* If manual control overides offboard, cancel the offboard setpoint and stay at current position */ + _reset_pos_sp = true; + _reset_alt_sp = true; - if (_control_mode.flag_control_altitude_enabled) { - _pos_sp(2) = _local_pos_sp.z; - } + /* Make sure position control is selected i.e. not only velocity control */ + if (_control_mode.flag_control_position_enabled) { + _pos_sp(0) = _local_pos_sp.x; + _pos_sp(1) = _local_pos_sp.y; + } - _att_sp.yaw_body = _local_pos_sp.yaw; + if (_control_mode.flag_control_altitude_enabled) { + _pos_sp(2) = _local_pos_sp.z; + } + + _att_sp.yaw_body = _local_pos_sp.yaw; + + } else { + reset_pos_sp(); + reset_alt_sp(); + } } else { /* AUTO */ -- cgit v1.2.3 From da2f68a6a09395a8d02a5d39bd3e92d7d0d79911 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 21 Jun 2014 14:25:29 +0200 Subject: mavlink: don't lock dataman when updating mission state --- src/modules/mavlink/mavlink_mission.cpp | 6 ------ 1 file changed, 6 deletions(-) diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 9bb956281..b2288469c 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -128,14 +128,8 @@ MavlinkMissionManager::update_active_mission(int dataman_id, unsigned count, int mission.current_seq = seq; /* update mission state in dataman */ - /* lock MISSION_STATE item */ - dm_lock(DM_KEY_MISSION_STATE); - int res = dm_write(DM_KEY_MISSION_STATE, 0, DM_PERSIST_POWER_ON_RESET, &mission, sizeof(mission_s)); - /* unlock MISSION_STATE item */ - dm_unlock(DM_KEY_MISSION_STATE); - if (res == sizeof(mission_s)) { /* update active mission state */ _dataman_id = dataman_id; -- cgit v1.2.3 From f1a5be1f57d9a15f29a428e962c3ed7f75777d22 Mon Sep 17 00:00:00 2001 From: Kynos Date: Sat, 21 Jun 2014 20:42:33 +0200 Subject: Define NAV-PVT message --- src/drivers/gps/ubx.h | 50 ++++++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 50 insertions(+) diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index f01b697a3..1a9e7cb0c 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -63,6 +63,7 @@ /* Message IDs */ #define UBX_ID_NAV_POSLLH 0x02 #define UBX_ID_NAV_SOL 0x06 +#define UBX_ID_NAV_PVT 0x07 #define UBX_ID_NAV_VELNED 0x12 #define UBX_ID_NAV_TIMEUTC 0x21 #define UBX_ID_NAV_SVINFO 0x30 @@ -78,6 +79,7 @@ /* Message Classes & IDs */ #define UBX_MSG_NAV_POSLLH ((UBX_CLASS_NAV) | UBX_ID_NAV_POSLLH << 8) #define UBX_MSG_NAV_SOL ((UBX_CLASS_NAV) | UBX_ID_NAV_SOL << 8) +#define UBX_MSG_NAV_PVT ((UBX_CLASS_NAV) | UBX_ID_NAV_PVT << 8) #define UBX_MSG_NAV_VELNED ((UBX_CLASS_NAV) | UBX_ID_NAV_VELNED << 8) #define UBX_MSG_NAV_TIMEUTC ((UBX_CLASS_NAV) | UBX_ID_NAV_TIMEUTC << 8) #define UBX_MSG_NAV_SVINFO ((UBX_CLASS_NAV) | UBX_ID_NAV_SVINFO << 8) @@ -90,6 +92,18 @@ #define UBX_MSG_MON_HW ((UBX_CLASS_MON) | UBX_ID_MON_HW << 8) #define UBX_MSG_MON_VER ((UBX_CLASS_MON) | UBX_ID_MON_VER << 8) +/* RX NAV-PVT message content details */ +/* Bitfield "valid" masks */ +#define UBX_RX_NAV_PVT_VALID_VALIDDATE 0x01 /**< validDate (Valid UTC Date) */ +#define UBX_RX_NAV_PVT_VALID_VALIDTIME 0x02 /**< validTime (Valid UTC Time) */ +#define UBX_RX_NAV_PVT_VALID_FULLYRESOLVED 0x04 /**< fullyResolved (1 = UTC Time of Day has been fully resolved (no seconds uncertainty)) */ + +/* Bitfield "flags" masks */ +#define UBX_RX_NAV_PVT_FLAGS_GNSSFIXOK 0x01 /**< gnssFixOK (A valid fix (i.e within DOP & accuracy masks)) */ +#define UBX_RX_NAV_PVT_FLAGS_DIFFSOLN 0x02 /**< diffSoln (1 if differential corrections were applied) */ +#define UBX_RX_NAV_PVT_FLAGS_PSMSTATE 0x1C /**< psmState (Power Save Mode state (see Power Management)) */ +#define UBX_RX_NAV_PVT_FLAGS_HEADVEHVALID 0x20 /**< headVehValid (Heading of vehicle is valid) */ + /* TX CFG-PRT message contents */ #define UBX_TX_CFG_PRT_PORTID 0x01 /**< UART1 */ #define UBX_TX_CFG_PRT_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ @@ -162,6 +176,42 @@ typedef struct { uint32_t reserved2; } ubx_payload_rx_nav_sol_t; +/* Rx NAV-PVT */ +typedef struct { + uint32_t iTOW; /**< GPS Time of Week [ms] */ + uint16_t year; /**< Year (UTC)*/ + uint8_t month; /**< Month, range 1..12 (UTC) */ + uint8_t day; /**< Day of month, range 1..31 (UTC) */ + uint8_t hour; /**< Hour of day, range 0..23 (UTC) */ + uint8_t min; /**< Minute of hour, range 0..59 (UTC) */ + uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */ + uint8_t valid; /**< Validity flags (see UBX_RX_NAV_PVT_VALID_...) */ + uint32_t tAcc; /**< Time accuracy estimate (UTC) [ns] */ + int32_t nano; /**< Fraction of second (UTC) [-1e9...1e9 ns] */ + uint8_t fixType; /**< GNSSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GNSS + dead reckoning, 5 = time only fix */ + uint8_t flags; /**< Fix Status Flags (see UBX_RX_NAV_PVT_FLAGS_...) */ + uint8_t reserved1; + uint8_t numSV; /**< Number of SVs used in Nav Solution */ + int32_t lon; /**< Longitude [1e-7 deg] */ + int32_t lat; /**< Latitude [1e-7 deg] */ + int32_t height; /**< Height above ellipsoid [mm] */ + int32_t hMSL; /**< Height above mean sea level [mm] */ + uint32_t hAcc; /**< Horizontal accuracy estimate [mm] */ + uint32_t vAcc; /**< Vertical accuracy estimate [mm] */ + int32_t velN; /**< NED north velocity [mm/s]*/ + int32_t velE; /**< NED east velocity [mm/s]*/ + int32_t velD; /**< NED down velocity [mm/s]*/ + int32_t gSpeed; /**< Ground Speed (2-D) [mm/s] */ + int32_t headMot; /**< Heading of motion (2-D) [1e-5 deg] */ + uint32_t sAcc; /**< Speed accuracy estimate [mm/s] */ + uint32_t headAcc; /**< Heading accuracy estimate (motion and vehicle) [1e-5 deg] */ + uint16_t pDOP; /**< Position DOP [0.01] */ + uint16_t reserved2; + uint32_t reserved3; + int32_t headVeh; /**< Heading of vehicle (2-D) [1e-5 deg] */ + uint32_t reserved4; +} ubx_payload_rx_nav_pvt_t; + /* Rx NAV-TIMEUTC */ typedef struct { uint32_t iTOW; /**< GPS Time of Week [ms] */ -- cgit v1.2.3 From 9f3758582f31066ba6ec0af2efc5c959fabb1baf Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 23 Jun 2014 10:18:16 +0200 Subject: update mavlink headers, headers generated with message definitions from the externalsetpoints branch of mavlink --- .../mavlink/v1.0/ardupilotmega/ardupilotmega.h | 122 ++++- .../v1.0/ardupilotmega/mavlink_msg_camera_event.h | 401 ++++++++++++++++ .../ardupilotmega/mavlink_msg_camera_feedback.h | 473 +++++++++++++++++++ .../include/mavlink/v1.0/ardupilotmega/testsuite.h | 126 +++++ .../include/mavlink/v1.0/ardupilotmega/version.h | 2 +- mavlink/include/mavlink/v1.0/autoquad/autoquad.h | 21 +- mavlink/include/mavlink/v1.0/autoquad/version.h | 2 +- mavlink/include/mavlink/v1.0/checksum.h | 2 +- mavlink/include/mavlink/v1.0/common/common.h | 146 +++--- .../mavlink_msg_attitude_setpoint_external.h | 393 ++++++++++++++++ .../v1.0/common/mavlink_msg_distance_sensor.h | 78 +-- ...ink_msg_global_position_setpoint_external_int.h | 497 ++++++++++++++++++++ .../mavlink/v1.0/common/mavlink_msg_heartbeat.h | 10 +- ...link_msg_local_ned_position_setpoint_external.h | 521 +++++++++++++++++++++ mavlink/include/mavlink/v1.0/common/testsuite.h | 204 +++++++- mavlink/include/mavlink/v1.0/common/version.h | 2 +- .../include/mavlink/v1.0/matrixpilot/matrixpilot.h | 21 +- mavlink/include/mavlink/v1.0/matrixpilot/version.h | 2 +- mavlink/include/mavlink/v1.0/mavlink_helpers.h | 21 +- mavlink/include/mavlink/v1.0/mavlink_types.h | 4 +- mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h | 21 +- mavlink/include/mavlink/v1.0/pixhawk/version.h | 2 +- mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h | 14 +- mavlink/include/mavlink/v1.0/sensesoar/version.h | 2 +- 24 files changed, 2917 insertions(+), 170 deletions(-) create mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_camera_event.h create mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_camera_feedback.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_setpoint_external.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_external_int.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_local_ned_position_setpoint_external.h diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h index c887dc68a..7e9173247 100644 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h @@ -5,6 +5,10 @@ #ifndef ARDUPILOTMEGA_H #define ARDUPILOTMEGA_H +#ifndef MAVLINK_H + #error Wrong include order: ARDUPILOTMEGA.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. +#endif + #ifdef __cplusplus extern "C" { #endif @@ -12,15 +16,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 41, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 212, 121, 172, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 206, 151, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, MAVLINK_MESSAGE_INFO_CAMERA_EVENT, MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" @@ -30,10 +34,65 @@ extern "C" { // ENUM DEFINITIONS +/** @brief */ +#ifndef HAVE_ENUM_MAV_CMD +#define HAVE_ENUM_MAV_CMD +typedef enum MAV_CMD +{ + MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ + MAV_CMD_NAV_ROI=80, /* 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. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ + MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ + MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ + MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ + MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ + 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_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 sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ + MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ + MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ + MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ + MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOTOR_TEST=209, /* Mission command to perform motor test |motor sequence number (a number from 1 to max number of motors on the vehicle)| throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)| throttle| timeout (in seconds)| Empty| Empty| Empty| */ + MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */ + 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| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ + MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ + 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| */ + MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ + MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ + MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ + MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ + MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ + MAV_CMD_ENUM_END=501, /* | */ +} MAV_CMD; +#endif + /** @brief */ #ifndef HAVE_ENUM_LIMITS_STATE #define HAVE_ENUM_LIMITS_STATE -enum LIMITS_STATE +typedef enum LIMITS_STATE { LIMITS_INIT=0, /* pre-initialization | */ LIMITS_DISABLED=1, /* disabled | */ @@ -42,42 +101,81 @@ enum LIMITS_STATE LIMITS_RECOVERING=4, /* taking action eg. RTL | */ LIMITS_RECOVERED=5, /* we're no longer in breach of a limit | */ LIMITS_STATE_ENUM_END=6, /* | */ -}; +} LIMITS_STATE; #endif /** @brief */ #ifndef HAVE_ENUM_LIMIT_MODULE #define HAVE_ENUM_LIMIT_MODULE -enum LIMIT_MODULE +typedef enum LIMIT_MODULE { LIMIT_GPSLOCK=1, /* pre-initialization | */ LIMIT_GEOFENCE=2, /* disabled | */ LIMIT_ALTITUDE=4, /* checking limits | */ LIMIT_MODULE_ENUM_END=5, /* | */ -}; +} LIMIT_MODULE; #endif /** @brief Flags in RALLY_POINT message */ #ifndef HAVE_ENUM_RALLY_FLAGS #define HAVE_ENUM_RALLY_FLAGS -enum RALLY_FLAGS +typedef enum RALLY_FLAGS { FAVORABLE_WIND=1, /* Flag set when requiring favorable winds for landing. | */ LAND_IMMEDIATELY=2, /* Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. | */ RALLY_FLAGS_ENUM_END=3, /* | */ -}; +} RALLY_FLAGS; #endif /** @brief */ #ifndef HAVE_ENUM_PARACHUTE_ACTION #define HAVE_ENUM_PARACHUTE_ACTION -enum PARACHUTE_ACTION +typedef enum PARACHUTE_ACTION { PARACHUTE_DISABLE=0, /* Disable parachute release | */ PARACHUTE_ENABLE=1, /* Enable parachute release | */ PARACHUTE_RELEASE=2, /* Release parachute | */ PARACHUTE_ACTION_ENUM_END=3, /* | */ -}; +} PARACHUTE_ACTION; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE +#define HAVE_ENUM_MOTOR_TEST_THROTTLE_TYPE +typedef enum MOTOR_TEST_THROTTLE_TYPE +{ + MOTOR_TEST_THROTTLE_PERCENT=0, /* throttle as a percentage from 0 ~ 100 | */ + MOTOR_TEST_THROTTLE_PWM=1, /* throttle as an absolute PWM value (normally in range of 1000~2000) | */ + MOTOR_TEST_THROTTLE_PILOT=2, /* throttle pass-through from pilot's transmitter | */ + MOTOR_TEST_THROTTLE_TYPE_ENUM_END=3, /* | */ +} MOTOR_TEST_THROTTLE_TYPE; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_CAMERA_EVENT_TYPES +#define HAVE_ENUM_CAMERA_EVENT_TYPES +typedef enum CAMERA_EVENT_TYPES +{ + HEARTBEAT=0, /* Camera heartbeat, announce camera component ID at 1hz | */ + TRIGGER=1, /* Camera image triggered | */ + DISCONNECT=2, /* Camera connection lost | */ + ERROR=3, /* Camera unknown error | */ + LOWBATT=4, /* Camera battery low. Parameter p1 shows reported voltage | */ + LOWSTORE=5, /* Camera storage low. Parameter p1 shows reported shots remaining | */ + LOWSTOREV=6, /* Camera storage low. Parameter p1 shows reported video minutes remaining | */ + CAMERA_EVENT_TYPES_ENUM_END=7, /* | */ +} CAMERA_EVENT_TYPES; +#endif + +/** @brief */ +#ifndef HAVE_ENUM_CAMERA_FEEDBACK_FLAGS +#define HAVE_ENUM_CAMERA_FEEDBACK_FLAGS +typedef enum CAMERA_FEEDBACK_FLAGS +{ + VIDEO=1, /* Shooting video, not stills | */ + BADEXPOSURE=2, /* Unable to achieve requested exposure (e.g. shutter speed too low) | */ + CAMERA_FEEDBACK_FLAGS_ENUM_END=3, /* | */ +} CAMERA_FEEDBACK_FLAGS; #endif #include "../common/common.h" @@ -122,6 +220,8 @@ enum PARACHUTE_ACTION #include "./mavlink_msg_rally_fetch_point.h" #include "./mavlink_msg_compassmot_status.h" #include "./mavlink_msg_ahrs2.h" +#include "./mavlink_msg_camera_event.h" +#include "./mavlink_msg_camera_feedback.h" #ifdef __cplusplus } diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_camera_event.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_camera_event.h new file mode 100644 index 000000000..82e7b3073 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_camera_event.h @@ -0,0 +1,401 @@ +// MESSAGE CAMERA_EVENT PACKING + +#define MAVLINK_MSG_ID_CAMERA_EVENT 179 + +typedef struct __mavlink_camera_event_t +{ + uint64_t time_usec; ///< Image timestamp (microseconds since UNIX epoch, according to camera clock) + float p1; ///< Parameter 1 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + float p2; ///< Parameter 2 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + float p3; ///< Parameter 3 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + float p4; ///< Parameter 4 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + uint16_t img_idx; ///< Image index + uint8_t target_system; ///< System ID + uint8_t cam_idx; ///< Camera ID + uint8_t event_id; ///< See CAMERA_EVENT_TYPES enum for definition of the bitmask +} mavlink_camera_event_t; + +#define MAVLINK_MSG_ID_CAMERA_EVENT_LEN 29 +#define MAVLINK_MSG_ID_179_LEN 29 + +#define MAVLINK_MSG_ID_CAMERA_EVENT_CRC 206 +#define MAVLINK_MSG_ID_179_CRC 206 + + + +#define MAVLINK_MESSAGE_INFO_CAMERA_EVENT { \ + "CAMERA_EVENT", \ + 9, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_event_t, time_usec) }, \ + { "p1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_event_t, p1) }, \ + { "p2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_event_t, p2) }, \ + { "p3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_event_t, p3) }, \ + { "p4", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_event_t, p4) }, \ + { "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_event_t, img_idx) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_camera_event_t, target_system) }, \ + { "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_camera_event_t, cam_idx) }, \ + { "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_event_t, event_id) }, \ + } \ +} + + +/** + * @brief Pack a camera_event message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Image timestamp (microseconds since UNIX epoch, according to camera clock) + * @param target_system System ID + * @param cam_idx Camera ID + * @param img_idx Image index + * @param event_id See CAMERA_EVENT_TYPES enum for definition of the bitmask + * @param p1 Parameter 1 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @param p2 Parameter 2 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @param p3 Parameter 3 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @param p4 Parameter 4 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_event_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_EVENT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, p1); + _mav_put_float(buf, 12, p2); + _mav_put_float(buf, 16, p3); + _mav_put_float(buf, 20, p4); + _mav_put_uint16_t(buf, 24, img_idx); + _mav_put_uint8_t(buf, 26, target_system); + _mav_put_uint8_t(buf, 27, cam_idx); + _mav_put_uint8_t(buf, 28, event_id); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#else + mavlink_camera_event_t packet; + packet.time_usec = time_usec; + packet.p1 = p1; + packet.p2 = p2; + packet.p3 = p3; + packet.p4 = p4; + packet.img_idx = img_idx; + packet.target_system = target_system; + packet.cam_idx = cam_idx; + packet.event_id = event_id; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_EVENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_EVENT_LEN, MAVLINK_MSG_ID_CAMERA_EVENT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#endif +} + +/** + * @brief Pack a camera_event message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Image timestamp (microseconds since UNIX epoch, according to camera clock) + * @param target_system System ID + * @param cam_idx Camera ID + * @param img_idx Image index + * @param event_id See CAMERA_EVENT_TYPES enum for definition of the bitmask + * @param p1 Parameter 1 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @param p2 Parameter 2 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @param p3 Parameter 3 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @param p4 Parameter 4 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_event_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t target_system,uint8_t cam_idx,uint16_t img_idx,uint8_t event_id,float p1,float p2,float p3,float p4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_EVENT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, p1); + _mav_put_float(buf, 12, p2); + _mav_put_float(buf, 16, p3); + _mav_put_float(buf, 20, p4); + _mav_put_uint16_t(buf, 24, img_idx); + _mav_put_uint8_t(buf, 26, target_system); + _mav_put_uint8_t(buf, 27, cam_idx); + _mav_put_uint8_t(buf, 28, event_id); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#else + mavlink_camera_event_t packet; + packet.time_usec = time_usec; + packet.p1 = p1; + packet.p2 = p2; + packet.p3 = p3; + packet.p4 = p4; + packet.img_idx = img_idx; + packet.target_system = target_system; + packet.cam_idx = cam_idx; + packet.event_id = event_id; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_EVENT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_EVENT_LEN, MAVLINK_MSG_ID_CAMERA_EVENT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#endif +} + +/** + * @brief Encode a camera_event struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param camera_event C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_event_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_event_t* camera_event) +{ + return mavlink_msg_camera_event_pack(system_id, component_id, msg, camera_event->time_usec, camera_event->target_system, camera_event->cam_idx, camera_event->img_idx, camera_event->event_id, camera_event->p1, camera_event->p2, camera_event->p3, camera_event->p4); +} + +/** + * @brief Encode a camera_event struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param camera_event C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_event_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_event_t* camera_event) +{ + return mavlink_msg_camera_event_pack_chan(system_id, component_id, chan, msg, camera_event->time_usec, camera_event->target_system, camera_event->cam_idx, camera_event->img_idx, camera_event->event_id, camera_event->p1, camera_event->p2, camera_event->p3, camera_event->p4); +} + +/** + * @brief Send a camera_event message + * @param chan MAVLink channel to send the message + * + * @param time_usec Image timestamp (microseconds since UNIX epoch, according to camera clock) + * @param target_system System ID + * @param cam_idx Camera ID + * @param img_idx Image index + * @param event_id See CAMERA_EVENT_TYPES enum for definition of the bitmask + * @param p1 Parameter 1 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @param p2 Parameter 2 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @param p3 Parameter 3 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + * @param p4 Parameter 4 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_camera_event_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_EVENT_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, p1); + _mav_put_float(buf, 12, p2); + _mav_put_float(buf, 16, p3); + _mav_put_float(buf, 20, p4); + _mav_put_uint16_t(buf, 24, img_idx); + _mav_put_uint8_t(buf, 26, target_system); + _mav_put_uint8_t(buf, 27, cam_idx); + _mav_put_uint8_t(buf, 28, event_id); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_EVENT, buf, MAVLINK_MSG_ID_CAMERA_EVENT_LEN, MAVLINK_MSG_ID_CAMERA_EVENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_EVENT, buf, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#endif +#else + mavlink_camera_event_t packet; + packet.time_usec = time_usec; + packet.p1 = p1; + packet.p2 = p2; + packet.p3 = p3; + packet.p4 = p4; + packet.img_idx = img_idx; + packet.target_system = target_system; + packet.cam_idx = cam_idx; + packet.event_id = event_id; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_EVENT, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_EVENT_LEN, MAVLINK_MSG_ID_CAMERA_EVENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_EVENT, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CAMERA_EVENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_camera_event_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_float(buf, 8, p1); + _mav_put_float(buf, 12, p2); + _mav_put_float(buf, 16, p3); + _mav_put_float(buf, 20, p4); + _mav_put_uint16_t(buf, 24, img_idx); + _mav_put_uint8_t(buf, 26, target_system); + _mav_put_uint8_t(buf, 27, cam_idx); + _mav_put_uint8_t(buf, 28, event_id); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_EVENT, buf, MAVLINK_MSG_ID_CAMERA_EVENT_LEN, MAVLINK_MSG_ID_CAMERA_EVENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_EVENT, buf, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#endif +#else + mavlink_camera_event_t *packet = (mavlink_camera_event_t *)msgbuf; + packet->time_usec = time_usec; + packet->p1 = p1; + packet->p2 = p2; + packet->p3 = p3; + packet->p4 = p4; + packet->img_idx = img_idx; + packet->target_system = target_system; + packet->cam_idx = cam_idx; + packet->event_id = event_id; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_EVENT, (const char *)packet, MAVLINK_MSG_ID_CAMERA_EVENT_LEN, MAVLINK_MSG_ID_CAMERA_EVENT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_EVENT, (const char *)packet, MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CAMERA_EVENT UNPACKING + + +/** + * @brief Get field time_usec from camera_event message + * + * @return Image timestamp (microseconds since UNIX epoch, according to camera clock) + */ +static inline uint64_t mavlink_msg_camera_event_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field target_system from camera_event message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_camera_event_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 26); +} + +/** + * @brief Get field cam_idx from camera_event message + * + * @return Camera ID + */ +static inline uint8_t mavlink_msg_camera_event_get_cam_idx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 27); +} + +/** + * @brief Get field img_idx from camera_event message + * + * @return Image index + */ +static inline uint16_t mavlink_msg_camera_event_get_img_idx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 24); +} + +/** + * @brief Get field event_id from camera_event message + * + * @return See CAMERA_EVENT_TYPES enum for definition of the bitmask + */ +static inline uint8_t mavlink_msg_camera_event_get_event_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 28); +} + +/** + * @brief Get field p1 from camera_event message + * + * @return Parameter 1 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + */ +static inline float mavlink_msg_camera_event_get_p1(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field p2 from camera_event message + * + * @return Parameter 2 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + */ +static inline float mavlink_msg_camera_event_get_p2(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field p3 from camera_event message + * + * @return Parameter 3 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + */ +static inline float mavlink_msg_camera_event_get_p3(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field p4 from camera_event message + * + * @return Parameter 4 (meaning depends on event, see CAMERA_EVENT_TYPES enum) + */ +static inline float mavlink_msg_camera_event_get_p4(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Decode a camera_event message into a struct + * + * @param msg The message to decode + * @param camera_event C-struct to decode the message contents into + */ +static inline void mavlink_msg_camera_event_decode(const mavlink_message_t* msg, mavlink_camera_event_t* camera_event) +{ +#if MAVLINK_NEED_BYTE_SWAP + camera_event->time_usec = mavlink_msg_camera_event_get_time_usec(msg); + camera_event->p1 = mavlink_msg_camera_event_get_p1(msg); + camera_event->p2 = mavlink_msg_camera_event_get_p2(msg); + camera_event->p3 = mavlink_msg_camera_event_get_p3(msg); + camera_event->p4 = mavlink_msg_camera_event_get_p4(msg); + camera_event->img_idx = mavlink_msg_camera_event_get_img_idx(msg); + camera_event->target_system = mavlink_msg_camera_event_get_target_system(msg); + camera_event->cam_idx = mavlink_msg_camera_event_get_cam_idx(msg); + camera_event->event_id = mavlink_msg_camera_event_get_event_id(msg); +#else + memcpy(camera_event, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CAMERA_EVENT_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_camera_feedback.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_camera_feedback.h new file mode 100644 index 000000000..a70029c56 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_camera_feedback.h @@ -0,0 +1,473 @@ +// MESSAGE CAMERA_FEEDBACK PACKING + +#define MAVLINK_MSG_ID_CAMERA_FEEDBACK 180 + +typedef struct __mavlink_camera_feedback_t +{ + uint64_t time_usec; ///< Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_EVENT message + int32_t lat; ///< Latitude in (deg * 1E7) + int32_t lng; ///< Longitude in (deg * 1E7) + float alt; ///< Altitude (meters, AMSL) + float roll; ///< Vehicle Roll angle (degrees, +-180) + float pitch; ///< Vehicle Pitch angle (degrees, +-180) + float yaw; ///< Vehicle Heading (degrees, 0-360, true) + float foc_len; ///< Focal Length (mm) + uint16_t img_idx; ///< Image index + uint8_t target_system; ///< System ID + uint8_t cam_idx; ///< Camera ID + uint8_t flags; ///< See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask +} mavlink_camera_feedback_t; + +#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN 41 +#define MAVLINK_MSG_ID_180_LEN 41 + +#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC 151 +#define MAVLINK_MSG_ID_180_CRC 151 + + + +#define MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK { \ + "CAMERA_FEEDBACK", \ + 12, \ + { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_feedback_t, time_usec) }, \ + { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_feedback_t, lat) }, \ + { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_feedback_t, lng) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_feedback_t, alt) }, \ + { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_feedback_t, roll) }, \ + { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_feedback_t, pitch) }, \ + { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_feedback_t, yaw) }, \ + { "foc_len", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_feedback_t, foc_len) }, \ + { "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_camera_feedback_t, img_idx) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_camera_feedback_t, target_system) }, \ + { "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_camera_feedback_t, cam_idx) }, \ + { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_camera_feedback_t, flags) }, \ + } \ +} + + +/** + * @brief Pack a camera_feedback message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_usec Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_EVENT message + * @param target_system System ID + * @param cam_idx Camera ID + * @param img_idx Image index + * @param lat Latitude in (deg * 1E7) + * @param lng Longitude in (deg * 1E7) + * @param alt Altitude (meters, AMSL) + * @param roll Vehicle Roll angle (degrees, +-180) + * @param pitch Vehicle Pitch angle (degrees, +-180) + * @param yaw Vehicle Heading (degrees, 0-360, true) + * @param foc_len Focal Length (mm) + * @param flags See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_feedback_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt, float roll, float pitch, float yaw, float foc_len, uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lng); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + _mav_put_float(buf, 32, foc_len); + _mav_put_uint16_t(buf, 36, img_idx); + _mav_put_uint8_t(buf, 38, target_system); + _mav_put_uint8_t(buf, 39, cam_idx); + _mav_put_uint8_t(buf, 40, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#else + mavlink_camera_feedback_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lng = lng; + packet.alt = alt; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.foc_len = foc_len; + packet.img_idx = img_idx; + packet.target_system = target_system; + packet.cam_idx = cam_idx; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_FEEDBACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#endif +} + +/** + * @brief Pack a camera_feedback message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_usec Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_EVENT message + * @param target_system System ID + * @param cam_idx Camera ID + * @param img_idx Image index + * @param lat Latitude in (deg * 1E7) + * @param lng Longitude in (deg * 1E7) + * @param alt Altitude (meters, AMSL) + * @param roll Vehicle Roll angle (degrees, +-180) + * @param pitch Vehicle Pitch angle (degrees, +-180) + * @param yaw Vehicle Heading (degrees, 0-360, true) + * @param foc_len Focal Length (mm) + * @param flags See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_camera_feedback_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint64_t time_usec,uint8_t target_system,uint8_t cam_idx,uint16_t img_idx,int32_t lat,int32_t lng,float alt,float roll,float pitch,float yaw,float foc_len,uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lng); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + _mav_put_float(buf, 32, foc_len); + _mav_put_uint16_t(buf, 36, img_idx); + _mav_put_uint8_t(buf, 38, target_system); + _mav_put_uint8_t(buf, 39, cam_idx); + _mav_put_uint8_t(buf, 40, flags); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#else + mavlink_camera_feedback_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lng = lng; + packet.alt = alt; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.foc_len = foc_len; + packet.img_idx = img_idx; + packet.target_system = target_system; + packet.cam_idx = cam_idx; + packet.flags = flags; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_CAMERA_FEEDBACK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#endif +} + +/** + * @brief Encode a camera_feedback struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param camera_feedback C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_feedback_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_feedback_t* camera_feedback) +{ + return mavlink_msg_camera_feedback_pack(system_id, component_id, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags); +} + +/** + * @brief Encode a camera_feedback struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param camera_feedback C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_camera_feedback_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_feedback_t* camera_feedback) +{ + return mavlink_msg_camera_feedback_pack_chan(system_id, component_id, chan, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags); +} + +/** + * @brief Send a camera_feedback message + * @param chan MAVLink channel to send the message + * + * @param time_usec Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_EVENT message + * @param target_system System ID + * @param cam_idx Camera ID + * @param img_idx Image index + * @param lat Latitude in (deg * 1E7) + * @param lng Longitude in (deg * 1E7) + * @param alt Altitude (meters, AMSL) + * @param roll Vehicle Roll angle (degrees, +-180) + * @param pitch Vehicle Pitch angle (degrees, +-180) + * @param yaw Vehicle Heading (degrees, 0-360, true) + * @param foc_len Focal Length (mm) + * @param flags See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_camera_feedback_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt, float roll, float pitch, float yaw, float foc_len, uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN]; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lng); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + _mav_put_float(buf, 32, foc_len); + _mav_put_uint16_t(buf, 36, img_idx); + _mav_put_uint8_t(buf, 38, target_system); + _mav_put_uint8_t(buf, 39, cam_idx); + _mav_put_uint8_t(buf, 40, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#endif +#else + mavlink_camera_feedback_t packet; + packet.time_usec = time_usec; + packet.lat = lat; + packet.lng = lng; + packet.alt = alt; + packet.roll = roll; + packet.pitch = pitch; + packet.yaw = yaw; + packet.foc_len = foc_len; + packet.img_idx = img_idx; + packet.target_system = target_system; + packet.cam_idx = cam_idx; + packet.flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_camera_feedback_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt, float roll, float pitch, float yaw, float foc_len, uint8_t flags) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint64_t(buf, 0, time_usec); + _mav_put_int32_t(buf, 8, lat); + _mav_put_int32_t(buf, 12, lng); + _mav_put_float(buf, 16, alt); + _mav_put_float(buf, 20, roll); + _mav_put_float(buf, 24, pitch); + _mav_put_float(buf, 28, yaw); + _mav_put_float(buf, 32, foc_len); + _mav_put_uint16_t(buf, 36, img_idx); + _mav_put_uint8_t(buf, 38, target_system); + _mav_put_uint8_t(buf, 39, cam_idx); + _mav_put_uint8_t(buf, 40, flags); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#endif +#else + mavlink_camera_feedback_t *packet = (mavlink_camera_feedback_t *)msgbuf; + packet->time_usec = time_usec; + packet->lat = lat; + packet->lng = lng; + packet->alt = alt; + packet->roll = roll; + packet->pitch = pitch; + packet->yaw = yaw; + packet->foc_len = foc_len; + packet->img_idx = img_idx; + packet->target_system = target_system; + packet->cam_idx = cam_idx; + packet->flags = flags; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE CAMERA_FEEDBACK UNPACKING + + +/** + * @brief Get field time_usec from camera_feedback message + * + * @return Image timestamp (microseconds since UNIX epoch), as passed in by CAMERA_EVENT message + */ +static inline uint64_t mavlink_msg_camera_feedback_get_time_usec(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint64_t(msg, 0); +} + +/** + * @brief Get field target_system from camera_feedback message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_camera_feedback_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 38); +} + +/** + * @brief Get field cam_idx from camera_feedback message + * + * @return Camera ID + */ +static inline uint8_t mavlink_msg_camera_feedback_get_cam_idx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 39); +} + +/** + * @brief Get field img_idx from camera_feedback message + * + * @return Image index + */ +static inline uint16_t mavlink_msg_camera_feedback_get_img_idx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 36); +} + +/** + * @brief Get field lat from camera_feedback message + * + * @return Latitude in (deg * 1E7) + */ +static inline int32_t mavlink_msg_camera_feedback_get_lat(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field lng from camera_feedback message + * + * @return Longitude in (deg * 1E7) + */ +static inline int32_t mavlink_msg_camera_feedback_get_lng(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field alt from camera_feedback message + * + * @return Altitude (meters, AMSL) + */ +static inline float mavlink_msg_camera_feedback_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field roll from camera_feedback message + * + * @return Vehicle Roll angle (degrees, +-180) + */ +static inline float mavlink_msg_camera_feedback_get_roll(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field pitch from camera_feedback message + * + * @return Vehicle Pitch angle (degrees, +-180) + */ +static inline float mavlink_msg_camera_feedback_get_pitch(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field yaw from camera_feedback message + * + * @return Vehicle Heading (degrees, 0-360, true) + */ +static inline float mavlink_msg_camera_feedback_get_yaw(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field foc_len from camera_feedback message + * + * @return Focal Length (mm) + */ +static inline float mavlink_msg_camera_feedback_get_foc_len(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field flags from camera_feedback message + * + * @return See CAMERA_FEEDBACK_FLAGS enum for definition of the bitmask + */ +static inline uint8_t mavlink_msg_camera_feedback_get_flags(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 40); +} + +/** + * @brief Decode a camera_feedback message into a struct + * + * @param msg The message to decode + * @param camera_feedback C-struct to decode the message contents into + */ +static inline void mavlink_msg_camera_feedback_decode(const mavlink_message_t* msg, mavlink_camera_feedback_t* camera_feedback) +{ +#if MAVLINK_NEED_BYTE_SWAP + camera_feedback->time_usec = mavlink_msg_camera_feedback_get_time_usec(msg); + camera_feedback->lat = mavlink_msg_camera_feedback_get_lat(msg); + camera_feedback->lng = mavlink_msg_camera_feedback_get_lng(msg); + camera_feedback->alt = mavlink_msg_camera_feedback_get_alt(msg); + camera_feedback->roll = mavlink_msg_camera_feedback_get_roll(msg); + camera_feedback->pitch = mavlink_msg_camera_feedback_get_pitch(msg); + camera_feedback->yaw = mavlink_msg_camera_feedback_get_yaw(msg); + camera_feedback->foc_len = mavlink_msg_camera_feedback_get_foc_len(msg); + camera_feedback->img_idx = mavlink_msg_camera_feedback_get_img_idx(msg); + camera_feedback->target_system = mavlink_msg_camera_feedback_get_target_system(msg); + camera_feedback->cam_idx = mavlink_msg_camera_feedback_get_cam_idx(msg); + camera_feedback->flags = mavlink_msg_camera_feedback_get_flags(msg); +#else + memcpy(camera_feedback, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h index 489553ea4..028a7d753 100644 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h @@ -1504,6 +1504,130 @@ static void mavlink_test_ahrs2(uint8_t system_id, uint8_t component_id, mavlink_ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_camera_event(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_camera_event_t packet_in = { + 93372036854775807ULL, + }73.0, + }101.0, + }129.0, + }157.0, + }18483, + }211, + }22, + }89, + }; + mavlink_camera_event_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.time_usec = packet_in.time_usec; + packet1.p1 = packet_in.p1; + packet1.p2 = packet_in.p2; + packet1.p3 = packet_in.p3; + packet1.p4 = packet_in.p4; + packet1.img_idx = packet_in.img_idx; + packet1.target_system = packet_in.target_system; + packet1.cam_idx = packet_in.cam_idx; + packet1.event_id = packet_in.event_id; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_camera_event_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_camera_event_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_camera_event_pack(system_id, component_id, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.event_id , packet1.p1 , packet1.p2 , packet1.p3 , packet1.p4 ); + mavlink_msg_camera_event_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_camera_event_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.event_id , packet1.p1 , packet1.p2 , packet1.p3 , packet1.p4 ); + mavlink_msg_camera_event_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ @@ -337,7 +334,7 @@ enum MAV_CMD MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ @@ -355,6 +352,7 @@ enum MAV_CMD MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */ 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| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ @@ -366,7 +364,7 @@ enum MAV_CMD MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ MAV_CMD_ENUM_END=501, /* | */ -}; +} MAV_CMD; #endif /** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a @@ -374,7 +372,7 @@ enum MAV_CMD the recommended messages. */ #ifndef HAVE_ENUM_MAV_DATA_STREAM #define HAVE_ENUM_MAV_DATA_STREAM -enum MAV_DATA_STREAM +typedef enum MAV_DATA_STREAM { MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ @@ -386,7 +384,7 @@ enum MAV_DATA_STREAM MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ MAV_DATA_STREAM_ENUM_END=13, /* | */ -}; +} MAV_DATA_STREAM; #endif /** @brief The ROI (region of interest) for the vehicle. This can be @@ -394,7 +392,7 @@ enum MAV_DATA_STREAM MAV_CMD_NAV_ROI). */ #ifndef HAVE_ENUM_MAV_ROI #define HAVE_ENUM_MAV_ROI -enum MAV_ROI +typedef enum MAV_ROI { MAV_ROI_NONE=0, /* No region of interest. | */ MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ @@ -402,13 +400,13 @@ enum MAV_ROI MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ MAV_ROI_TARGET=4, /* Point toward of given id. | */ MAV_ROI_ENUM_END=5, /* | */ -}; +} MAV_ROI; #endif /** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ #ifndef HAVE_ENUM_MAV_CMD_ACK #define HAVE_ENUM_MAV_CMD_ACK -enum MAV_CMD_ACK +typedef enum MAV_CMD_ACK { MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ @@ -420,13 +418,13 @@ enum MAV_CMD_ACK MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ MAV_CMD_ACK_ENUM_END=10, /* | */ -}; +} MAV_CMD_ACK; #endif /** @brief Specifies the datatype of a MAVLink parameter. */ #ifndef HAVE_ENUM_MAV_PARAM_TYPE #define HAVE_ENUM_MAV_PARAM_TYPE -enum MAV_PARAM_TYPE +typedef enum MAV_PARAM_TYPE { MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */ MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */ @@ -439,13 +437,13 @@ enum MAV_PARAM_TYPE MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */ MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */ MAV_PARAM_TYPE_ENUM_END=11, /* | */ -}; +} MAV_PARAM_TYPE; #endif /** @brief result from a mavlink command */ #ifndef HAVE_ENUM_MAV_RESULT #define HAVE_ENUM_MAV_RESULT -enum MAV_RESULT +typedef enum MAV_RESULT { MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ @@ -453,13 +451,13 @@ enum MAV_RESULT MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ MAV_RESULT_FAILED=4, /* Command executed, but failed | */ MAV_RESULT_ENUM_END=5, /* | */ -}; +} MAV_RESULT; #endif /** @brief result in a mavlink mission ack */ #ifndef HAVE_ENUM_MAV_MISSION_RESULT #define HAVE_ENUM_MAV_MISSION_RESULT -enum MAV_MISSION_RESULT +typedef enum MAV_MISSION_RESULT { MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ @@ -477,13 +475,13 @@ enum MAV_MISSION_RESULT MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ MAV_MISSION_RESULT_ENUM_END=15, /* | */ -}; +} MAV_MISSION_RESULT; #endif /** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ #ifndef HAVE_ENUM_MAV_SEVERITY #define HAVE_ENUM_MAV_SEVERITY -enum MAV_SEVERITY +typedef enum MAV_SEVERITY { MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ @@ -494,13 +492,13 @@ enum MAV_SEVERITY MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ MAV_SEVERITY_ENUM_END=8, /* | */ -}; +} MAV_SEVERITY; #endif /** @brief Power supply status flags (bitmask) */ #ifndef HAVE_ENUM_MAV_POWER_STATUS #define HAVE_ENUM_MAV_POWER_STATUS -enum MAV_POWER_STATUS +typedef enum MAV_POWER_STATUS { MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */ MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */ @@ -509,26 +507,26 @@ enum MAV_POWER_STATUS MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */ MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */ MAV_POWER_STATUS_ENUM_END=33, /* | */ -}; +} MAV_POWER_STATUS; #endif /** @brief SERIAL_CONTROL device types */ #ifndef HAVE_ENUM_SERIAL_CONTROL_DEV #define HAVE_ENUM_SERIAL_CONTROL_DEV -enum SERIAL_CONTROL_DEV +typedef enum SERIAL_CONTROL_DEV { SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */ SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */ SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */ SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */ SERIAL_CONTROL_DEV_ENUM_END=4, /* | */ -}; +} SERIAL_CONTROL_DEV; #endif /** @brief SERIAL_CONTROL flags (bitmask) */ #ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG #define HAVE_ENUM_SERIAL_CONTROL_FLAG -enum SERIAL_CONTROL_FLAG +typedef enum SERIAL_CONTROL_FLAG { SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */ SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */ @@ -536,7 +534,18 @@ enum SERIAL_CONTROL_FLAG SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */ SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */ SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */ -}; +} SERIAL_CONTROL_FLAG; +#endif + +/** @brief Enumeration of distance sensor types */ +#ifndef HAVE_ENUM_MAV_DISTANCE_SENSOR +#define HAVE_ENUM_MAV_DISTANCE_SENSOR +typedef enum MAV_DISTANCE_SENSOR +{ + MAV_DISTANCE_SENSOR_LASER=0, /* Laser altimeter, e.g. LightWare SF02/F or PulsedLight units | */ + MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Ultrasound altimeter, e.g. MaxBotix units | */ + MAV_DISTANCE_SENSOR_ENUM_END=2, /* | */ +} MAV_DISTANCE_SENSOR; #endif @@ -616,6 +625,9 @@ enum SERIAL_CONTROL_FLAG #include "./mavlink_msg_command_ack.h" #include "./mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h" #include "./mavlink_msg_manual_setpoint.h" +#include "./mavlink_msg_attitude_setpoint_external.h" +#include "./mavlink_msg_local_ned_position_setpoint_external.h" +#include "./mavlink_msg_global_position_setpoint_external_int.h" #include "./mavlink_msg_local_position_ned_system_global_offset.h" #include "./mavlink_msg_hil_state.h" #include "./mavlink_msg_hil_controls.h" diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_setpoint_external.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_setpoint_external.h new file mode 100644 index 000000000..d50179f45 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_setpoint_external.h @@ -0,0 +1,393 @@ +// MESSAGE ATTITUDE_SETPOINT_EXTERNAL PACKING + +#define MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL 82 + +typedef struct __mavlink_attitude_setpoint_external_t +{ + uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot + float q[4]; ///< Quaternion + float body_roll_rate; ///< Body roll rate in radians per second + float body_pitch_rate; ///< Body roll rate in radians per second + float body_yaw_rate; ///< Body roll rate in radians per second + float thrust; ///< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t ignore_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: roll, bit 2: pitch, bit 3: yaw, bit 4: roll rate, bit 5: pitch rate, bit 6: yaw rate, bit 7: thrust +} mavlink_attitude_setpoint_external_t; + +#define MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN 39 +#define MAVLINK_MSG_ID_82_LEN 39 + +#define MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC 212 +#define MAVLINK_MSG_ID_82_CRC 212 + +#define MAVLINK_MSG_ATTITUDE_SETPOINT_EXTERNAL_FIELD_Q_LEN 4 + +#define MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL { \ + "ATTITUDE_SETPOINT_EXTERNAL", \ + 9, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_setpoint_external_t, time_boot_ms) }, \ + { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_setpoint_external_t, q) }, \ + { "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_setpoint_external_t, body_roll_rate) }, \ + { "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_setpoint_external_t, body_pitch_rate) }, \ + { "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_setpoint_external_t, body_yaw_rate) }, \ + { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_setpoint_external_t, thrust) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_setpoint_external_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_attitude_setpoint_external_t, target_component) }, \ + { "ignore_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_attitude_setpoint_external_t, ignore_mask) }, \ + } \ +} + + +/** + * @brief Pack a attitude_setpoint_external message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: roll, bit 2: pitch, bit 3: yaw, bit 4: roll rate, bit 5: pitch rate, bit 6: yaw rate, bit 7: thrust + * @param q Quaternion + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_setpoint_external_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t ignore_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, ignore_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#else + mavlink_attitude_setpoint_external_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + packet.ignore_mask = ignore_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#endif +} + +/** + * @brief Pack a attitude_setpoint_external message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: roll, bit 2: pitch, bit 3: yaw, bit 4: roll rate, bit 5: pitch rate, bit 6: yaw rate, bit 7: thrust + * @param q Quaternion + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_attitude_setpoint_external_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t ignore_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, ignore_mask); + _mav_put_float_array(buf, 4, q, 4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#else + mavlink_attitude_setpoint_external_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + packet.ignore_mask = ignore_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#endif +} + +/** + * @brief Encode a attitude_setpoint_external struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param attitude_setpoint_external C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_setpoint_external_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_setpoint_external_t* attitude_setpoint_external) +{ + return mavlink_msg_attitude_setpoint_external_pack(system_id, component_id, msg, attitude_setpoint_external->time_boot_ms, attitude_setpoint_external->target_system, attitude_setpoint_external->target_component, attitude_setpoint_external->ignore_mask, attitude_setpoint_external->q, attitude_setpoint_external->body_roll_rate, attitude_setpoint_external->body_pitch_rate, attitude_setpoint_external->body_yaw_rate, attitude_setpoint_external->thrust); +} + +/** + * @brief Encode a attitude_setpoint_external struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param attitude_setpoint_external C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_attitude_setpoint_external_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_setpoint_external_t* attitude_setpoint_external) +{ + return mavlink_msg_attitude_setpoint_external_pack_chan(system_id, component_id, chan, msg, attitude_setpoint_external->time_boot_ms, attitude_setpoint_external->target_system, attitude_setpoint_external->target_component, attitude_setpoint_external->ignore_mask, attitude_setpoint_external->q, attitude_setpoint_external->body_roll_rate, attitude_setpoint_external->body_pitch_rate, attitude_setpoint_external->body_yaw_rate, attitude_setpoint_external->thrust); +} + +/** + * @brief Send a attitude_setpoint_external message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: roll, bit 2: pitch, bit 3: yaw, bit 4: roll rate, bit 5: pitch rate, bit 6: yaw rate, bit 7: thrust + * @param q Quaternion + * @param body_roll_rate Body roll rate in radians per second + * @param body_pitch_rate Body roll rate in radians per second + * @param body_yaw_rate Body roll rate in radians per second + * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_attitude_setpoint_external_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t ignore_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, ignore_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL, buf, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL, buf, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#endif +#else + mavlink_attitude_setpoint_external_t packet; + packet.time_boot_ms = time_boot_ms; + packet.body_roll_rate = body_roll_rate; + packet.body_pitch_rate = body_pitch_rate; + packet.body_yaw_rate = body_yaw_rate; + packet.thrust = thrust; + packet.target_system = target_system; + packet.target_component = target_component; + packet.ignore_mask = ignore_mask; + mav_array_memcpy(packet.q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_attitude_setpoint_external_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t ignore_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 20, body_roll_rate); + _mav_put_float(buf, 24, body_pitch_rate); + _mav_put_float(buf, 28, body_yaw_rate); + _mav_put_float(buf, 32, thrust); + _mav_put_uint8_t(buf, 36, target_system); + _mav_put_uint8_t(buf, 37, target_component); + _mav_put_uint8_t(buf, 38, ignore_mask); + _mav_put_float_array(buf, 4, q, 4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL, buf, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL, buf, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#endif +#else + mavlink_attitude_setpoint_external_t *packet = (mavlink_attitude_setpoint_external_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->body_roll_rate = body_roll_rate; + packet->body_pitch_rate = body_pitch_rate; + packet->body_yaw_rate = body_yaw_rate; + packet->thrust = thrust; + packet->target_system = target_system; + packet->target_component = target_component; + packet->ignore_mask = ignore_mask; + mav_array_memcpy(packet->q, q, sizeof(float)*4); +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE ATTITUDE_SETPOINT_EXTERNAL UNPACKING + + +/** + * @brief Get field time_boot_ms from attitude_setpoint_external message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_attitude_setpoint_external_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field target_system from attitude_setpoint_external message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_attitude_setpoint_external_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 36); +} + +/** + * @brief Get field target_component from attitude_setpoint_external message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_attitude_setpoint_external_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 37); +} + +/** + * @brief Get field ignore_mask from attitude_setpoint_external message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: roll, bit 2: pitch, bit 3: yaw, bit 4: roll rate, bit 5: pitch rate, bit 6: yaw rate, bit 7: thrust + */ +static inline uint8_t mavlink_msg_attitude_setpoint_external_get_ignore_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 38); +} + +/** + * @brief Get field q from attitude_setpoint_external message + * + * @return Quaternion + */ +static inline uint16_t mavlink_msg_attitude_setpoint_external_get_q(const mavlink_message_t* msg, float *q) +{ + return _MAV_RETURN_float_array(msg, q, 4, 4); +} + +/** + * @brief Get field body_roll_rate from attitude_setpoint_external message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_attitude_setpoint_external_get_body_roll_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field body_pitch_rate from attitude_setpoint_external message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_attitude_setpoint_external_get_body_pitch_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field body_yaw_rate from attitude_setpoint_external message + * + * @return Body roll rate in radians per second + */ +static inline float mavlink_msg_attitude_setpoint_external_get_body_yaw_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field thrust from attitude_setpoint_external message + * + * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust) + */ +static inline float mavlink_msg_attitude_setpoint_external_get_thrust(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Decode a attitude_setpoint_external message into a struct + * + * @param msg The message to decode + * @param attitude_setpoint_external C-struct to decode the message contents into + */ +static inline void mavlink_msg_attitude_setpoint_external_decode(const mavlink_message_t* msg, mavlink_attitude_setpoint_external_t* attitude_setpoint_external) +{ +#if MAVLINK_NEED_BYTE_SWAP + attitude_setpoint_external->time_boot_ms = mavlink_msg_attitude_setpoint_external_get_time_boot_ms(msg); + mavlink_msg_attitude_setpoint_external_get_q(msg, attitude_setpoint_external->q); + attitude_setpoint_external->body_roll_rate = mavlink_msg_attitude_setpoint_external_get_body_roll_rate(msg); + attitude_setpoint_external->body_pitch_rate = mavlink_msg_attitude_setpoint_external_get_body_pitch_rate(msg); + attitude_setpoint_external->body_yaw_rate = mavlink_msg_attitude_setpoint_external_get_body_yaw_rate(msg); + attitude_setpoint_external->thrust = mavlink_msg_attitude_setpoint_external_get_thrust(msg); + attitude_setpoint_external->target_system = mavlink_msg_attitude_setpoint_external_get_target_system(msg); + attitude_setpoint_external->target_component = mavlink_msg_attitude_setpoint_external_get_target_component(msg); + attitude_setpoint_external->ignore_mask = mavlink_msg_attitude_setpoint_external_get_ignore_mask(msg); +#else + memcpy(attitude_setpoint_external, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_SETPOINT_EXTERNAL_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h index 39b384396..8743b6485 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h @@ -44,17 +44,17 @@ typedef struct __mavlink_distance_sensor_t * @param msg The MAVLink message to compress the data into * * @param time_boot_ms Time since system boot - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from FIXME enum. * @param min_distance Minimum distance the sensor can measure in centimeters * @param max_distance Maximum distance the sensor can measure in centimeters * @param current_distance Current distance reading + * @param type Type from MAV_DISTANCE_SENSOR enum. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces from FIXME enum. * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t type, uint8_t id, uint8_t orientation, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t covariance) + uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; @@ -97,18 +97,18 @@ static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8 * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into * @param time_boot_ms Time since system boot - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from FIXME enum. * @param min_distance Minimum distance the sensor can measure in centimeters * @param max_distance Maximum distance the sensor can measure in centimeters * @param current_distance Current distance reading + * @param type Type from MAV_DISTANCE_SENSOR enum. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces from FIXME enum. * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t type,uint8_t id,uint8_t orientation,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t covariance) + uint32_t time_boot_ms,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t type,uint8_t id,uint8_t orientation,uint8_t covariance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; @@ -154,7 +154,7 @@ static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, */ static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) { - return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->covariance); + return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); } /** @@ -168,7 +168,7 @@ static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uin */ static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) { - return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->covariance); + return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance); } /** @@ -176,17 +176,17 @@ static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id * @param chan MAVLink channel to send the message * * @param time_boot_ms Time since system boot - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from FIXME enum. * @param min_distance Minimum distance the sensor can measure in centimeters * @param max_distance Maximum distance the sensor can measure in centimeters * @param current_distance Current distance reading + * @param type Type from MAV_DISTANCE_SENSOR enum. + * @param id Onboard ID of the sensor + * @param orientation Direction the sensor faces from FIXME enum. * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type, uint8_t id, uint8_t orientation, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t covariance) +static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; @@ -231,7 +231,7 @@ static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type, uint8_t id, uint8_t orientation, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t covariance) +static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -285,63 +285,63 @@ static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlin } /** - * @brief Get field type from distance_sensor message + * @brief Get field min_distance from distance_sensor message * - * @return Type from MAV_DISTANCE_SENSOR enum. + * @return Minimum distance the sensor can measure in centimeters */ -static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg) +static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 10); + return _MAV_RETURN_uint16_t(msg, 4); } /** - * @brief Get field id from distance_sensor message + * @brief Get field max_distance from distance_sensor message * - * @return Onboard ID of the sensor + * @return Maximum distance the sensor can measure in centimeters */ -static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg) +static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 11); + return _MAV_RETURN_uint16_t(msg, 6); } /** - * @brief Get field orientation from distance_sensor message + * @brief Get field current_distance from distance_sensor message * - * @return Direction the sensor faces from FIXME enum. + * @return Current distance reading */ -static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg) +static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg) { - return _MAV_RETURN_uint8_t(msg, 12); + return _MAV_RETURN_uint16_t(msg, 8); } /** - * @brief Get field min_distance from distance_sensor message + * @brief Get field type from distance_sensor message * - * @return Minimum distance the sensor can measure in centimeters + * @return Type from MAV_DISTANCE_SENSOR enum. */ -static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg) +static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 4); + return _MAV_RETURN_uint8_t(msg, 10); } /** - * @brief Get field max_distance from distance_sensor message + * @brief Get field id from distance_sensor message * - * @return Maximum distance the sensor can measure in centimeters + * @return Onboard ID of the sensor */ -static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg) +static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 6); + return _MAV_RETURN_uint8_t(msg, 11); } /** - * @brief Get field current_distance from distance_sensor message + * @brief Get field orientation from distance_sensor message * - * @return Current distance reading + * @return Direction the sensor faces from FIXME enum. */ -static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg) +static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg) { - return _MAV_RETURN_uint16_t(msg, 8); + return _MAV_RETURN_uint8_t(msg, 12); } /** diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_external_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_external_int.h new file mode 100644 index 000000000..46ab556d8 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_external_int.h @@ -0,0 +1,497 @@ +// MESSAGE GLOBAL_POSITION_SETPOINT_EXTERNAL_INT PACKING + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT 84 + +typedef struct __mavlink_global_position_setpoint_external_int_t +{ + uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + int32_t lat_int; ///< X Position in WGS84 frame in 1e7 * meters + int32_t lon_int; ///< Y Position in WGS84 frame in 1e7 * meters + float alt; ///< Altitude in WGS84, not AMSL + float vx; ///< X velocity in NED frame in meter / s + float vy; ///< Y velocity in NED frame in meter / s + float vz; ///< Z velocity in NED frame in meter / s + float ax; ///< X acceleration in NED frame in meter / s^2 + float ay; ///< Y acceleration in NED frame in meter / s^2 + float az; ///< Z acceleration in NED frame in meter / s^2 + uint16_t ignore_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID +} mavlink_global_position_setpoint_external_int_t; + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN 44 +#define MAVLINK_MSG_ID_84_LEN 44 + +#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC 172 +#define MAVLINK_MSG_ID_84_CRC 172 + + + +#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT { \ + "GLOBAL_POSITION_SETPOINT_EXTERNAL_INT", \ + 13, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_setpoint_external_int_t, time_boot_ms) }, \ + { "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_setpoint_external_int_t, lat_int) }, \ + { "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_setpoint_external_int_t, lon_int) }, \ + { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_position_setpoint_external_int_t, alt) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_setpoint_external_int_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_setpoint_external_int_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_setpoint_external_int_t, vz) }, \ + { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_setpoint_external_int_t, ax) }, \ + { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_setpoint_external_int_t, ay) }, \ + { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_setpoint_external_int_t, az) }, \ + { "ignore_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_global_position_setpoint_external_int_t, ignore_mask) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_global_position_setpoint_external_int_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_global_position_setpoint_external_int_t, target_component) }, \ + } \ +} + + +/** + * @brief Pack a global_position_setpoint_external_int message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in WGS84, not AMSL + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param ax X acceleration in NED frame in meter / s^2 + * @param ay Y acceleration in NED frame in meter / s^2 + * @param az Z acceleration in NED frame in meter / s^2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint16_t ignore_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float ax, float ay, float az) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, ax); + _mav_put_float(buf, 32, ay); + _mav_put_float(buf, 36, az); + _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_uint8_t(buf, 42, target_system); + _mav_put_uint8_t(buf, 43, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#else + mavlink_global_position_setpoint_external_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.ignore_mask = ignore_mask; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#endif +} + +/** + * @brief Pack a global_position_setpoint_external_int message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in WGS84, not AMSL + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param ax X acceleration in NED frame in meter / s^2 + * @param ay Y acceleration in NED frame in meter / s^2 + * @param az Z acceleration in NED frame in meter / s^2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint16_t ignore_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float ax,float ay,float az) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, ax); + _mav_put_float(buf, 32, ay); + _mav_put_float(buf, 36, az); + _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_uint8_t(buf, 42, target_system); + _mav_put_uint8_t(buf, 43, target_component); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#else + mavlink_global_position_setpoint_external_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.ignore_mask = ignore_mask; + packet.target_system = target_system; + packet.target_component = target_component; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#endif +} + +/** + * @brief Encode a global_position_setpoint_external_int struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param global_position_setpoint_external_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_setpoint_external_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_setpoint_external_int_t* global_position_setpoint_external_int) +{ + return mavlink_msg_global_position_setpoint_external_int_pack(system_id, component_id, msg, global_position_setpoint_external_int->time_boot_ms, global_position_setpoint_external_int->target_system, global_position_setpoint_external_int->target_component, global_position_setpoint_external_int->ignore_mask, global_position_setpoint_external_int->lat_int, global_position_setpoint_external_int->lon_int, global_position_setpoint_external_int->alt, global_position_setpoint_external_int->vx, global_position_setpoint_external_int->vy, global_position_setpoint_external_int->vz, global_position_setpoint_external_int->ax, global_position_setpoint_external_int->ay, global_position_setpoint_external_int->az); +} + +/** + * @brief Encode a global_position_setpoint_external_int struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param global_position_setpoint_external_int C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_global_position_setpoint_external_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_setpoint_external_int_t* global_position_setpoint_external_int) +{ + return mavlink_msg_global_position_setpoint_external_int_pack_chan(system_id, component_id, chan, msg, global_position_setpoint_external_int->time_boot_ms, global_position_setpoint_external_int->target_system, global_position_setpoint_external_int->target_component, global_position_setpoint_external_int->ignore_mask, global_position_setpoint_external_int->lat_int, global_position_setpoint_external_int->lon_int, global_position_setpoint_external_int->alt, global_position_setpoint_external_int->vx, global_position_setpoint_external_int->vy, global_position_setpoint_external_int->vz, global_position_setpoint_external_int->ax, global_position_setpoint_external_int->ay, global_position_setpoint_external_int->az); +} + +/** + * @brief Send a global_position_setpoint_external_int message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + * @param target_system System ID + * @param target_component Component ID + * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param lat_int X Position in WGS84 frame in 1e7 * meters + * @param lon_int Y Position in WGS84 frame in 1e7 * meters + * @param alt Altitude in WGS84, not AMSL + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param ax X acceleration in NED frame in meter / s^2 + * @param ay Y acceleration in NED frame in meter / s^2 + * @param az Z acceleration in NED frame in meter / s^2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_global_position_setpoint_external_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint16_t ignore_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float ax, float ay, float az) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, ax); + _mav_put_float(buf, 32, ay); + _mav_put_float(buf, 36, az); + _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_uint8_t(buf, 42, target_system); + _mav_put_uint8_t(buf, 43, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#endif +#else + mavlink_global_position_setpoint_external_int_t packet; + packet.time_boot_ms = time_boot_ms; + packet.lat_int = lat_int; + packet.lon_int = lon_int; + packet.alt = alt; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.ignore_mask = ignore_mask; + packet.target_system = target_system; + packet.target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_global_position_setpoint_external_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint16_t ignore_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float ax, float ay, float az) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_int32_t(buf, 4, lat_int); + _mav_put_int32_t(buf, 8, lon_int); + _mav_put_float(buf, 12, alt); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, ax); + _mav_put_float(buf, 32, ay); + _mav_put_float(buf, 36, az); + _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_uint8_t(buf, 42, target_system); + _mav_put_uint8_t(buf, 43, target_component); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#endif +#else + mavlink_global_position_setpoint_external_int_t *packet = (mavlink_global_position_setpoint_external_int_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->lat_int = lat_int; + packet->lon_int = lon_int; + packet->alt = alt; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->ax = ax; + packet->ay = ay; + packet->az = az; + packet->ignore_mask = ignore_mask; + packet->target_system = target_system; + packet->target_component = target_component; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GLOBAL_POSITION_SETPOINT_EXTERNAL_INT UNPACKING + + +/** + * @brief Get field time_boot_ms from global_position_setpoint_external_int message + * + * @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. + */ +static inline uint32_t mavlink_msg_global_position_setpoint_external_int_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field target_system from global_position_setpoint_external_int message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_global_position_setpoint_external_int_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field target_component from global_position_setpoint_external_int message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_global_position_setpoint_external_int_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 43); +} + +/** + * @brief Get field ignore_mask from global_position_setpoint_external_int message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + */ +static inline uint16_t mavlink_msg_global_position_setpoint_external_int_get_ignore_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 40); +} + +/** + * @brief Get field lat_int from global_position_setpoint_external_int message + * + * @return X Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_global_position_setpoint_external_int_get_lat_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 4); +} + +/** + * @brief Get field lon_int from global_position_setpoint_external_int message + * + * @return Y Position in WGS84 frame in 1e7 * meters + */ +static inline int32_t mavlink_msg_global_position_setpoint_external_int_get_lon_int(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field alt from global_position_setpoint_external_int message + * + * @return Altitude in WGS84, not AMSL + */ +static inline float mavlink_msg_global_position_setpoint_external_int_get_alt(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from global_position_setpoint_external_int message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_global_position_setpoint_external_int_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from global_position_setpoint_external_int message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_global_position_setpoint_external_int_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from global_position_setpoint_external_int message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_global_position_setpoint_external_int_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field ax from global_position_setpoint_external_int message + * + * @return X acceleration in NED frame in meter / s^2 + */ +static inline float mavlink_msg_global_position_setpoint_external_int_get_ax(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field ay from global_position_setpoint_external_int message + * + * @return Y acceleration in NED frame in meter / s^2 + */ +static inline float mavlink_msg_global_position_setpoint_external_int_get_ay(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field az from global_position_setpoint_external_int message + * + * @return Z acceleration in NED frame in meter / s^2 + */ +static inline float mavlink_msg_global_position_setpoint_external_int_get_az(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a global_position_setpoint_external_int message into a struct + * + * @param msg The message to decode + * @param global_position_setpoint_external_int C-struct to decode the message contents into + */ +static inline void mavlink_msg_global_position_setpoint_external_int_decode(const mavlink_message_t* msg, mavlink_global_position_setpoint_external_int_t* global_position_setpoint_external_int) +{ +#if MAVLINK_NEED_BYTE_SWAP + global_position_setpoint_external_int->time_boot_ms = mavlink_msg_global_position_setpoint_external_int_get_time_boot_ms(msg); + global_position_setpoint_external_int->lat_int = mavlink_msg_global_position_setpoint_external_int_get_lat_int(msg); + global_position_setpoint_external_int->lon_int = mavlink_msg_global_position_setpoint_external_int_get_lon_int(msg); + global_position_setpoint_external_int->alt = mavlink_msg_global_position_setpoint_external_int_get_alt(msg); + global_position_setpoint_external_int->vx = mavlink_msg_global_position_setpoint_external_int_get_vx(msg); + global_position_setpoint_external_int->vy = mavlink_msg_global_position_setpoint_external_int_get_vy(msg); + global_position_setpoint_external_int->vz = mavlink_msg_global_position_setpoint_external_int_get_vz(msg); + global_position_setpoint_external_int->ax = mavlink_msg_global_position_setpoint_external_int_get_ax(msg); + global_position_setpoint_external_int->ay = mavlink_msg_global_position_setpoint_external_int_get_ay(msg); + global_position_setpoint_external_int->az = mavlink_msg_global_position_setpoint_external_int_get_az(msg); + global_position_setpoint_external_int->ignore_mask = mavlink_msg_global_position_setpoint_external_int_get_ignore_mask(msg); + global_position_setpoint_external_int->target_system = mavlink_msg_global_position_setpoint_external_int_get_target_system(msg); + global_position_setpoint_external_int->target_component = mavlink_msg_global_position_setpoint_external_int_get_target_component(msg); +#else + memcpy(global_position_setpoint_external_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h index 902e381ca..733886b9a 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h @@ -7,7 +7,7 @@ typedef struct __mavlink_heartbeat_t uint32_t custom_mode; ///< A bitfield for use for autopilot-specific flags. uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) uint8_t autopilot; ///< Autopilot type / class. defined in MAV_AUTOPILOT ENUM - uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h uint8_t system_status; ///< System status flag, see MAV_STATE ENUM uint8_t mavlink_version; ///< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version } mavlink_heartbeat_t; @@ -41,7 +41,7 @@ typedef struct __mavlink_heartbeat_t * * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h * @param custom_mode A bitfield for use for autopilot-specific flags. * @param system_status System status flag, see MAV_STATE ENUM * @return length of the message in bytes (excluding serial stream start sign) @@ -87,7 +87,7 @@ static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t com * @param msg The MAVLink message to compress the data into * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h * @param custom_mode A bitfield for use for autopilot-specific flags. * @param system_status System status flag, see MAV_STATE ENUM * @return length of the message in bytes (excluding serial stream start sign) @@ -159,7 +159,7 @@ static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint * * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @param base_mode System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h * @param custom_mode A bitfield for use for autopilot-specific flags. * @param system_status System status flag, see MAV_STATE ENUM */ @@ -268,7 +268,7 @@ static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_ /** * @brief Get field base_mode from heartbeat message * - * @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h + * @return System mode bitfield, see MAV_MODE_FLAG ENUM in mavlink/include/mavlink_types.h */ static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) { diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_ned_position_setpoint_external.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_ned_position_setpoint_external.h new file mode 100644 index 000000000..6e60578ce --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_ned_position_setpoint_external.h @@ -0,0 +1,521 @@ +// MESSAGE LOCAL_NED_POSITION_SETPOINT_EXTERNAL PACKING + +#define MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL 83 + +typedef struct __mavlink_local_ned_position_setpoint_external_t +{ + uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot + float x; ///< X Position in NED frame in meters + float y; ///< Y Position in NED frame in meters + float z; ///< Z Position in NED frame in meters (note, altitude is negative in NED) + float vx; ///< X velocity in NED frame in meter / s + float vy; ///< Y velocity in NED frame in meter / s + float vz; ///< Z velocity in NED frame in meter / s + float ax; ///< X acceleration in NED frame in meter / s^2 + float ay; ///< Y acceleration in NED frame in meter / s^2 + float az; ///< Z acceleration in NED frame in meter / s^2 + uint16_t ignore_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + uint8_t target_system; ///< System ID + uint8_t target_component; ///< Component ID + uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 +} mavlink_local_ned_position_setpoint_external_t; + +#define MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN 45 +#define MAVLINK_MSG_ID_83_LEN 45 + +#define MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC 121 +#define MAVLINK_MSG_ID_83_CRC 121 + + + +#define MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL { \ + "LOCAL_NED_POSITION_SETPOINT_EXTERNAL", \ + 14, \ + { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_ned_position_setpoint_external_t, time_boot_ms) }, \ + { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_ned_position_setpoint_external_t, x) }, \ + { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_ned_position_setpoint_external_t, y) }, \ + { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_ned_position_setpoint_external_t, z) }, \ + { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_ned_position_setpoint_external_t, vx) }, \ + { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_ned_position_setpoint_external_t, vy) }, \ + { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_ned_position_setpoint_external_t, vz) }, \ + { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_ned_position_setpoint_external_t, ax) }, \ + { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_ned_position_setpoint_external_t, ay) }, \ + { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_ned_position_setpoint_external_t, az) }, \ + { "ignore_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_local_ned_position_setpoint_external_t, ignore_mask) }, \ + { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_local_ned_position_setpoint_external_t, target_system) }, \ + { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_local_ned_position_setpoint_external_t, target_component) }, \ + { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_local_ned_position_setpoint_external_t, coordinate_frame) }, \ + } \ +} + + +/** + * @brief Pack a local_ned_position_setpoint_external message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 + * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param ax X acceleration in NED frame in meter / s^2 + * @param ay Y acceleration in NED frame in meter / s^2 + * @param az Z acceleration in NED frame in meter / s^2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t ignore_mask, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, ax); + _mav_put_float(buf, 32, ay); + _mav_put_float(buf, 36, az); + _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_uint8_t(buf, 42, target_system); + _mav_put_uint8_t(buf, 43, target_component); + _mav_put_uint8_t(buf, 44, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#else + mavlink_local_ned_position_setpoint_external_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.ignore_mask = ignore_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#endif +} + +/** + * @brief Pack a local_ned_position_setpoint_external message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 + * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param ax X acceleration in NED frame in meter / s^2 + * @param ay Y acceleration in NED frame in meter / s^2 + * @param az Z acceleration in NED frame in meter / s^2 + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t ignore_mask,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, ax); + _mav_put_float(buf, 32, ay); + _mav_put_float(buf, 36, az); + _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_uint8_t(buf, 42, target_system); + _mav_put_uint8_t(buf, 43, target_component); + _mav_put_uint8_t(buf, 44, coordinate_frame); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#else + mavlink_local_ned_position_setpoint_external_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.ignore_mask = ignore_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#endif +} + +/** + * @brief Encode a local_ned_position_setpoint_external struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param local_ned_position_setpoint_external C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_ned_position_setpoint_external_t* local_ned_position_setpoint_external) +{ + return mavlink_msg_local_ned_position_setpoint_external_pack(system_id, component_id, msg, local_ned_position_setpoint_external->time_boot_ms, local_ned_position_setpoint_external->target_system, local_ned_position_setpoint_external->target_component, local_ned_position_setpoint_external->coordinate_frame, local_ned_position_setpoint_external->ignore_mask, local_ned_position_setpoint_external->x, local_ned_position_setpoint_external->y, local_ned_position_setpoint_external->z, local_ned_position_setpoint_external->vx, local_ned_position_setpoint_external->vy, local_ned_position_setpoint_external->vz, local_ned_position_setpoint_external->ax, local_ned_position_setpoint_external->ay, local_ned_position_setpoint_external->az); +} + +/** + * @brief Encode a local_ned_position_setpoint_external struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param local_ned_position_setpoint_external C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_ned_position_setpoint_external_t* local_ned_position_setpoint_external) +{ + return mavlink_msg_local_ned_position_setpoint_external_pack_chan(system_id, component_id, chan, msg, local_ned_position_setpoint_external->time_boot_ms, local_ned_position_setpoint_external->target_system, local_ned_position_setpoint_external->target_component, local_ned_position_setpoint_external->coordinate_frame, local_ned_position_setpoint_external->ignore_mask, local_ned_position_setpoint_external->x, local_ned_position_setpoint_external->y, local_ned_position_setpoint_external->z, local_ned_position_setpoint_external->vx, local_ned_position_setpoint_external->vy, local_ned_position_setpoint_external->vz, local_ned_position_setpoint_external->ax, local_ned_position_setpoint_external->ay, local_ned_position_setpoint_external->az); +} + +/** + * @brief Send a local_ned_position_setpoint_external message + * @param chan MAVLink channel to send the message + * + * @param time_boot_ms Timestamp in milliseconds since system boot + * @param target_system System ID + * @param target_component Component ID + * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 + * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param x X Position in NED frame in meters + * @param y Y Position in NED frame in meters + * @param z Z Position in NED frame in meters (note, altitude is negative in NED) + * @param vx X velocity in NED frame in meter / s + * @param vy Y velocity in NED frame in meter / s + * @param vz Z velocity in NED frame in meter / s + * @param ax X acceleration in NED frame in meter / s^2 + * @param ay Y acceleration in NED frame in meter / s^2 + * @param az Z acceleration in NED frame in meter / s^2 + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_local_ned_position_setpoint_external_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t ignore_mask, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN]; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, ax); + _mav_put_float(buf, 32, ay); + _mav_put_float(buf, 36, az); + _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_uint8_t(buf, 42, target_system); + _mav_put_uint8_t(buf, 43, target_component); + _mav_put_uint8_t(buf, 44, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, buf, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, buf, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#endif +#else + mavlink_local_ned_position_setpoint_external_t packet; + packet.time_boot_ms = time_boot_ms; + packet.x = x; + packet.y = y; + packet.z = z; + packet.vx = vx; + packet.vy = vy; + packet.vz = vz; + packet.ax = ax; + packet.ay = ay; + packet.az = az; + packet.ignore_mask = ignore_mask; + packet.target_system = target_system; + packet.target_component = target_component; + packet.coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_local_ned_position_setpoint_external_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t ignore_mask, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_boot_ms); + _mav_put_float(buf, 4, x); + _mav_put_float(buf, 8, y); + _mav_put_float(buf, 12, z); + _mav_put_float(buf, 16, vx); + _mav_put_float(buf, 20, vy); + _mav_put_float(buf, 24, vz); + _mav_put_float(buf, 28, ax); + _mav_put_float(buf, 32, ay); + _mav_put_float(buf, 36, az); + _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_uint8_t(buf, 42, target_system); + _mav_put_uint8_t(buf, 43, target_component); + _mav_put_uint8_t(buf, 44, coordinate_frame); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, buf, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, buf, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#endif +#else + mavlink_local_ned_position_setpoint_external_t *packet = (mavlink_local_ned_position_setpoint_external_t *)msgbuf; + packet->time_boot_ms = time_boot_ms; + packet->x = x; + packet->y = y; + packet->z = z; + packet->vx = vx; + packet->vy = vy; + packet->vz = vz; + packet->ax = ax; + packet->ay = ay; + packet->az = az; + packet->ignore_mask = ignore_mask; + packet->target_system = target_system; + packet->target_component = target_component; + packet->coordinate_frame = coordinate_frame; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, (const char *)packet, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, (const char *)packet, MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE LOCAL_NED_POSITION_SETPOINT_EXTERNAL UNPACKING + + +/** + * @brief Get field time_boot_ms from local_ned_position_setpoint_external message + * + * @return Timestamp in milliseconds since system boot + */ +static inline uint32_t mavlink_msg_local_ned_position_setpoint_external_get_time_boot_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field target_system from local_ned_position_setpoint_external message + * + * @return System ID + */ +static inline uint8_t mavlink_msg_local_ned_position_setpoint_external_get_target_system(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 42); +} + +/** + * @brief Get field target_component from local_ned_position_setpoint_external message + * + * @return Component ID + */ +static inline uint8_t mavlink_msg_local_ned_position_setpoint_external_get_target_component(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 43); +} + +/** + * @brief Get field coordinate_frame from local_ned_position_setpoint_external message + * + * @return Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 + */ +static inline uint8_t mavlink_msg_local_ned_position_setpoint_external_get_coordinate_frame(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 44); +} + +/** + * @brief Get field ignore_mask from local_ned_position_setpoint_external message + * + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + */ +static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_get_ignore_mask(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 40); +} + +/** + * @brief Get field x from local_ned_position_setpoint_external message + * + * @return X Position in NED frame in meters + */ +static inline float mavlink_msg_local_ned_position_setpoint_external_get_x(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 4); +} + +/** + * @brief Get field y from local_ned_position_setpoint_external message + * + * @return Y Position in NED frame in meters + */ +static inline float mavlink_msg_local_ned_position_setpoint_external_get_y(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 8); +} + +/** + * @brief Get field z from local_ned_position_setpoint_external message + * + * @return Z Position in NED frame in meters (note, altitude is negative in NED) + */ +static inline float mavlink_msg_local_ned_position_setpoint_external_get_z(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 12); +} + +/** + * @brief Get field vx from local_ned_position_setpoint_external message + * + * @return X velocity in NED frame in meter / s + */ +static inline float mavlink_msg_local_ned_position_setpoint_external_get_vx(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 16); +} + +/** + * @brief Get field vy from local_ned_position_setpoint_external message + * + * @return Y velocity in NED frame in meter / s + */ +static inline float mavlink_msg_local_ned_position_setpoint_external_get_vy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 20); +} + +/** + * @brief Get field vz from local_ned_position_setpoint_external message + * + * @return Z velocity in NED frame in meter / s + */ +static inline float mavlink_msg_local_ned_position_setpoint_external_get_vz(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 24); +} + +/** + * @brief Get field ax from local_ned_position_setpoint_external message + * + * @return X acceleration in NED frame in meter / s^2 + */ +static inline float mavlink_msg_local_ned_position_setpoint_external_get_ax(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 28); +} + +/** + * @brief Get field ay from local_ned_position_setpoint_external message + * + * @return Y acceleration in NED frame in meter / s^2 + */ +static inline float mavlink_msg_local_ned_position_setpoint_external_get_ay(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 32); +} + +/** + * @brief Get field az from local_ned_position_setpoint_external message + * + * @return Z acceleration in NED frame in meter / s^2 + */ +static inline float mavlink_msg_local_ned_position_setpoint_external_get_az(const mavlink_message_t* msg) +{ + return _MAV_RETURN_float(msg, 36); +} + +/** + * @brief Decode a local_ned_position_setpoint_external message into a struct + * + * @param msg The message to decode + * @param local_ned_position_setpoint_external C-struct to decode the message contents into + */ +static inline void mavlink_msg_local_ned_position_setpoint_external_decode(const mavlink_message_t* msg, mavlink_local_ned_position_setpoint_external_t* local_ned_position_setpoint_external) +{ +#if MAVLINK_NEED_BYTE_SWAP + local_ned_position_setpoint_external->time_boot_ms = mavlink_msg_local_ned_position_setpoint_external_get_time_boot_ms(msg); + local_ned_position_setpoint_external->x = mavlink_msg_local_ned_position_setpoint_external_get_x(msg); + local_ned_position_setpoint_external->y = mavlink_msg_local_ned_position_setpoint_external_get_y(msg); + local_ned_position_setpoint_external->z = mavlink_msg_local_ned_position_setpoint_external_get_z(msg); + local_ned_position_setpoint_external->vx = mavlink_msg_local_ned_position_setpoint_external_get_vx(msg); + local_ned_position_setpoint_external->vy = mavlink_msg_local_ned_position_setpoint_external_get_vy(msg); + local_ned_position_setpoint_external->vz = mavlink_msg_local_ned_position_setpoint_external_get_vz(msg); + local_ned_position_setpoint_external->ax = mavlink_msg_local_ned_position_setpoint_external_get_ax(msg); + local_ned_position_setpoint_external->ay = mavlink_msg_local_ned_position_setpoint_external_get_ay(msg); + local_ned_position_setpoint_external->az = mavlink_msg_local_ned_position_setpoint_external_get_az(msg); + local_ned_position_setpoint_external->ignore_mask = mavlink_msg_local_ned_position_setpoint_external_get_ignore_mask(msg); + local_ned_position_setpoint_external->target_system = mavlink_msg_local_ned_position_setpoint_external_get_target_system(msg); + local_ned_position_setpoint_external->target_component = mavlink_msg_local_ned_position_setpoint_external_get_target_component(msg); + local_ned_position_setpoint_external->coordinate_frame = mavlink_msg_local_ned_position_setpoint_external_get_coordinate_frame(msg); +#else + memcpy(local_ned_position_setpoint_external, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/testsuite.h b/mavlink/include/mavlink/v1.0/common/testsuite.h index de23fcb2a..ccfe74f08 100644 --- a/mavlink/include/mavlink/v1.0/common/testsuite.h +++ b/mavlink/include/mavlink/v1.0/common/testsuite.h @@ -3367,6 +3367,201 @@ static void mavlink_test_manual_setpoint(uint8_t system_id, uint8_t component_id MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_attitude_setpoint_external(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_attitude_setpoint_external_t packet_in = { + 963497464, + }{ 45.0, 46.0, 47.0, 48.0 }, + }157.0, + }185.0, + }213.0, + }241.0, + }113, + }180, + }247, + }; + mavlink_attitude_setpoint_external_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.time_boot_ms = packet_in.time_boot_ms; + packet1.body_roll_rate = packet_in.body_roll_rate; + packet1.body_pitch_rate = packet_in.body_pitch_rate; + packet1.body_yaw_rate = packet_in.body_yaw_rate; + packet1.thrust = packet_in.thrust; + packet1.target_system = packet_in.target_system; + packet1.target_component = packet_in.target_component; + packet1.ignore_mask = packet_in.ignore_mask; + + mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4); + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_attitude_setpoint_external_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_attitude_setpoint_external_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_attitude_setpoint_external_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.ignore_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); + mavlink_msg_attitude_setpoint_external_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_attitude_setpoint_external_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.ignore_mask , packet1.q , packet1.body_roll_rate , packet1.body_pitch_rate , packet1.body_yaw_rate , packet1.thrust ); + mavlink_msg_attitude_setpoint_external_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ @@ -68,7 +72,7 @@ enum MAV_CMD MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ @@ -86,6 +90,7 @@ enum MAV_CMD MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */ 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| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ @@ -97,7 +102,7 @@ enum MAV_CMD MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ MAV_CMD_ENUM_END=501, /* | */ -}; +} MAV_CMD; #endif #include "../common/common.h" diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/version.h b/mavlink/include/mavlink/v1.0/matrixpilot/version.h index 50cbda6c7..40273061d 100644 --- a/mavlink/include/mavlink/v1.0/matrixpilot/version.h +++ b/mavlink/include/mavlink/v1.0/matrixpilot/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Sun Apr 13 09:38:32 2014" +#define MAVLINK_BUILD_DATE "Mon Jun 23 10:13:29 2014" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/mavlink/include/mavlink/v1.0/mavlink_helpers.h b/mavlink/include/mavlink/v1.0/mavlink_helpers.h index 96672f847..1639a830b 100644 --- a/mavlink/include/mavlink/v1.0/mavlink_helpers.h +++ b/mavlink/include/mavlink/v1.0/mavlink_helpers.h @@ -73,7 +73,6 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui #endif { // This code part is the same for all messages; - uint16_t checksum; msg->magic = MAVLINK_STX; msg->len = length; msg->sysid = system_id; @@ -81,12 +80,13 @@ MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, ui // One sequence number per component msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; - checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN); + msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN); + crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len); #if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); + crc_accumulate(crc_extra, &msg->checksum); #endif - mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF); - mavlink_ck_b(msg) = (uint8_t)(checksum >> 8); + mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF); + mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8); return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; } @@ -133,7 +133,7 @@ MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint buf[4] = mavlink_system.compid; buf[5] = msgid; status->current_tx_seq++; - checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); + checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); crc_accumulate_buffer(&checksum, packet, length); #if MAVLINK_CRC_EXTRA crc_accumulate(crc_extra, &checksum); @@ -158,6 +158,7 @@ MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_m ck[0] = (uint8_t)(msg->checksum & 0xFF); ck[1] = (uint8_t)(msg->checksum >> 8); + // XXX use the right sequence here MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES); @@ -172,7 +173,13 @@ MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_m */ MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) { - memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); + memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); + + uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); + + ck[0] = (uint8_t)(msg->checksum & 0xFF); + ck[1] = (uint8_t)(msg->checksum >> 8); + return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; } diff --git a/mavlink/include/mavlink/v1.0/mavlink_types.h b/mavlink/include/mavlink/v1.0/mavlink_types.h index 4019c619e..43658e629 100644 --- a/mavlink/include/mavlink/v1.0/mavlink_types.h +++ b/mavlink/include/mavlink/v1.0/mavlink_types.h @@ -28,6 +28,7 @@ #define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) +#pragma pack(push, 1) typedef struct param_union { union { float param_float; @@ -62,13 +63,12 @@ typedef struct __mavlink_message { uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; } mavlink_message_t; - typedef struct __mavlink_extended_message { mavlink_message_t base_msg; int32_t extended_payload_len; ///< Length of extended payload if any uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; } mavlink_extended_message_t; - +#pragma pack(pop) typedef enum { MAVLINK_TYPE_CHAR = 0, diff --git a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h index a624a2579..6a55f592b 100644 --- a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h @@ -5,6 +5,10 @@ #ifndef PIXHAWK_H #define PIXHAWK_H +#ifndef MAVLINK_H + #error Wrong include order: PIXHAWK.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. +#endif + #ifdef __cplusplus extern "C" { #endif @@ -12,15 +16,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 0, 0, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 0, 0, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 0, 0, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 212, 121, 172, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 0, 0, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" @@ -33,19 +37,19 @@ extern "C" { /** @brief Content Types for data transmission handshake */ #ifndef HAVE_ENUM_DATA_TYPES #define HAVE_ENUM_DATA_TYPES -enum DATA_TYPES +typedef enum DATA_TYPES { DATA_TYPE_JPEG_IMAGE=1, /* | */ DATA_TYPE_RAW_IMAGE=2, /* | */ DATA_TYPE_KINECT=3, /* | */ DATA_TYPES_ENUM_END=4, /* | */ -}; +} DATA_TYPES; #endif /** @brief */ #ifndef HAVE_ENUM_MAV_CMD #define HAVE_ENUM_MAV_CMD -enum MAV_CMD +typedef enum MAV_CMD { MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ @@ -63,7 +67,7 @@ enum MAV_CMD MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Custom mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ @@ -81,6 +85,7 @@ enum MAV_CMD MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ + MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight |inverted (0=normal, 1=inverted)| Empty| Empty| Empty| Empty| Empty| Empty| */ MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */ 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| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ @@ -95,7 +100,7 @@ enum MAV_CMD MAV_CMD_DO_START_SEARCH=10001, /* Starts a search |1 to arm, 0 to disarm| */ MAV_CMD_DO_FINISH_SEARCH=10002, /* Starts a search |1 to arm, 0 to disarm| */ MAV_CMD_NAV_SWEEP=10003, /* Starts a search |1 to arm, 0 to disarm| */ -}; +} MAV_CMD; #endif #include "../common/common.h" diff --git a/mavlink/include/mavlink/v1.0/pixhawk/version.h b/mavlink/include/mavlink/v1.0/pixhawk/version.h index 6610a894c..6a639918e 100644 --- a/mavlink/include/mavlink/v1.0/pixhawk/version.h +++ b/mavlink/include/mavlink/v1.0/pixhawk/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Sun Apr 13 09:38:46 2014" +#define MAVLINK_BUILD_DATE "Mon Jun 23 10:13:53 2014" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h b/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h index 2eab86354..4fb651853 100644 --- a/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h +++ b/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h @@ -5,6 +5,10 @@ #ifndef SENSESOAR_H #define SENSESOAR_H +#ifndef MAVLINK_H + #error Wrong include order: SENSESOAR.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call. +#endif + #ifdef __cplusplus extern "C" { #endif @@ -12,15 +16,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 212, 121, 172, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" @@ -33,13 +37,13 @@ extern "C" { /** @brief Different flight modes */ #ifndef HAVE_ENUM_SENSESOAR_MODE #define HAVE_ENUM_SENSESOAR_MODE -enum SENSESOAR_MODE +typedef enum SENSESOAR_MODE { SENSESOAR_MODE_GLIDING=1, /* Gliding mode with motors off | */ SENSESOAR_MODE_AUTONOMOUS=2, /* Autonomous flight | */ SENSESOAR_MODE_MANUAL=3, /* RC controlled | */ SENSESOAR_MODE_ENUM_END=4, /* | */ -}; +} SENSESOAR_MODE; #endif #include "../common/common.h" diff --git a/mavlink/include/mavlink/v1.0/sensesoar/version.h b/mavlink/include/mavlink/v1.0/sensesoar/version.h index 78d562803..de8a60750 100644 --- a/mavlink/include/mavlink/v1.0/sensesoar/version.h +++ b/mavlink/include/mavlink/v1.0/sensesoar/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Sun Apr 13 09:39:00 2014" +#define MAVLINK_BUILD_DATE "Mon Jun 23 10:13:41 2014" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 -- cgit v1.2.3 From 88adeee6695a2160f9eac130d3923129728dd008 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 23 Jun 2014 13:35:14 +0200 Subject: define force setpoint uorb topic --- src/modules/uORB/objects_common.cpp | 3 ++ src/modules/uORB/topics/vehicle_force_setpoint.h | 65 ++++++++++++++++++++++++ 2 files changed, 68 insertions(+) create mode 100644 src/modules/uORB/topics/vehicle_force_setpoint.h diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp index 90675bb2e..d45314222 100644 --- a/src/modules/uORB/objects_common.cpp +++ b/src/modules/uORB/objects_common.cpp @@ -199,3 +199,6 @@ ORB_DEFINE(encoders, struct encoders_s); #include "topics/estimator_status.h" ORB_DEFINE(estimator_status, struct estimator_status_report); + +#include "topics/vehicle_force_setpoint.h" +ORB_DEFINE(vehicle_force_setpoint, struct vehicle_force_setpoint_s); diff --git a/src/modules/uORB/topics/vehicle_force_setpoint.h b/src/modules/uORB/topics/vehicle_force_setpoint.h new file mode 100644 index 000000000..c7b5f558e --- /dev/null +++ b/src/modules/uORB/topics/vehicle_force_setpoint.h @@ -0,0 +1,65 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * Author: @author Thomas Gubler + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file vehicle_local_force_setpoint.h + * @author Thomas Gubler + * Definition of force (NED) setpoint uORB topic. Typically this can be used + * by a position control app togeth with an attitude control app. + */ + +#ifndef TOPIC_VEHICLE_FORCE_SETPOINT_H_ +#define TOPIC_VEHICLE_FORCE_SETPOINT_H_ + +#include "../uORB.h" + +/** + * @addtogroup topics + * @{ + */ + +struct vehicle_force_setpoint_s { + float x; /**< in N NED */ + float y; /**< in N NED */ + float z; /**< in N NED */ +}; /**< Desired force in NED frame */ + +/** + * @} + */ + +/* register this as object request broker structure */ +ORB_DECLARE(vehicle_force_setpoint); + +#endif -- cgit v1.2.3 From 179bace35aaa32a23ebd7a9cb99d54eae53690f5 Mon Sep 17 00:00:00 2001 From: Antonio Sanniravong Date: Tue, 24 Jun 2014 07:47:16 -0400 Subject: Resets XY velocities when we can't estimate them --- src/modules/position_estimator_inav/position_estimator_inav_main.c | 7 +++++++ .../position_estimator_inav/position_estimator_inav_params.c | 3 +++ .../position_estimator_inav/position_estimator_inav_params.h | 2 ++ 3 files changed, 12 insertions(+) diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c index f908d7a3b..5f132453b 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -916,6 +916,10 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) memcpy(x_est_prev, x_est, sizeof(x_est)); memcpy(y_est_prev, y_est, sizeof(y_est)); } + } else { + /* gradually reset xy velocity estimates */ + inertial_filter_correct(-x_est[1], dt, x_est, 1, params.w_xy_reset_v); + inertial_filter_correct(-y_est[1], dt, y_est, 1, params.w_xy_reset_v); } /* detect land */ @@ -931,6 +935,9 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) landed = false; landed_time = 0; } + /* reset xy velocity estimates when landed */ + x_est[1] = 0.0f; + y_est[1] = 0.0f; } else { if (alt_disp2 < land_disp2 && thrust < params.land_thr) { diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c index d88419c25..b79e00274 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c @@ -46,6 +46,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f); +PARAM_DEFINE_FLOAT(INAV_W_XY_RESET_V, 0.2f); PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f); PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f); PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.15f); @@ -65,6 +66,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h) h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P"); h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V"); h->w_xy_flow = param_find("INAV_W_XY_FLOW"); + h->w_xy_reset_v = param_find("INAV_W_XY_RESET_V"); h->w_gps_flow = param_find("INAV_W_GPS_FLOW"); h->w_acc_bias = param_find("INAV_W_ACC_BIAS"); h->flow_k = param_find("INAV_FLOW_K"); @@ -87,6 +89,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str param_get(h->w_xy_gps_p, &(p->w_xy_gps_p)); param_get(h->w_xy_gps_v, &(p->w_xy_gps_v)); param_get(h->w_xy_flow, &(p->w_xy_flow)); + param_get(h->w_xy_reset_v, &(p->w_xy_reset_v)); param_get(h->w_gps_flow, &(p->w_gps_flow)); param_get(h->w_acc_bias, &(p->w_acc_bias)); param_get(h->flow_k, &(p->flow_k)); diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h index df1cfaa71..9be13637d 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.h +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h @@ -47,6 +47,7 @@ struct position_estimator_inav_params { float w_xy_gps_p; float w_xy_gps_v; float w_xy_flow; + float w_xy_reset_v; float w_gps_flow; float w_acc_bias; float flow_k; @@ -66,6 +67,7 @@ struct position_estimator_inav_param_handles { param_t w_xy_gps_p; param_t w_xy_gps_v; param_t w_xy_flow; + param_t w_xy_reset_v; param_t w_gps_flow; param_t w_acc_bias; param_t flow_k; -- cgit v1.2.3 From 3ddb502d2e1b07705bfaa59c89528d53d0444303 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 24 Jun 2014 14:14:13 +0200 Subject: force setpoint: fix comment --- src/modules/uORB/topics/vehicle_force_setpoint.h | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/modules/uORB/topics/vehicle_force_setpoint.h b/src/modules/uORB/topics/vehicle_force_setpoint.h index c7b5f558e..cd948985f 100644 --- a/src/modules/uORB/topics/vehicle_force_setpoint.h +++ b/src/modules/uORB/topics/vehicle_force_setpoint.h @@ -1,7 +1,6 @@ /**************************************************************************** * * Copyright (C) 2014 PX4 Development Team. All rights reserved. - * Author: @author Thomas Gubler * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -33,10 +32,10 @@ ****************************************************************************/ /** - * @file vehicle_local_force_setpoint.h + * @file vehicle_force_setpoint.h * @author Thomas Gubler * Definition of force (NED) setpoint uORB topic. Typically this can be used - * by a position control app togeth with an attitude control app. + * by a position control app together with an attitude control app. */ #ifndef TOPIC_VEHICLE_FORCE_SETPOINT_H_ -- cgit v1.2.3 From be33b4b6a56402135e5cfb8b38e0cc0ae8b7d673 Mon Sep 17 00:00:00 2001 From: holger Date: Tue, 24 Jun 2014 19:28:39 +0200 Subject: UAVCAN: append to EXTRADEFINES to those given by make cmd line --- src/modules/uavcan/module.mk | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index ce9f981a8..5ac7019e3 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -52,7 +52,7 @@ SRCS += $(LIBUAVCAN_SRC) INCLUDE_DIRS += $(LIBUAVCAN_INC) # Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile # because this platform lacks most of the standard library and STL. Hence we need to force C++03 mode. -EXTRADEFINES += -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 +override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 # # libuavcan drivers for STM32 @@ -60,8 +60,7 @@ EXTRADEFINES += -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 include $(UAVCAN_DIR)/libuavcan_drivers/stm32/driver/include.mk SRCS += $(LIBUAVCAN_STM32_SRC) INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC) -EXTRADEFINES += -DUAVCAN_STM32_NUTTX \ - -DUAVCAN_STM32_NUM_IFACES=2 +override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=2 # # Invoke DSDL compiler -- cgit v1.2.3 From 211c721b48c5856ace7f09e88706d799299ca6bb Mon Sep 17 00:00:00 2001 From: Antonio Sanniravong Date: Tue, 24 Jun 2014 17:42:25 -0400 Subject: Shorten the reset param name to INAV_W_XY_RES_V --- src/modules/position_estimator_inav/position_estimator_inav_main.c | 4 ++-- .../position_estimator_inav/position_estimator_inav_params.c | 6 +++--- .../position_estimator_inav/position_estimator_inav_params.h | 4 ++-- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/modules/position_estimator_inav/position_estimator_inav_main.c b/src/modules/position_estimator_inav/position_estimator_inav_main.c index 5f132453b..eca406acf 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_main.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_main.c @@ -918,8 +918,8 @@ int position_estimator_inav_thread_main(int argc, char *argv[]) } } else { /* gradually reset xy velocity estimates */ - inertial_filter_correct(-x_est[1], dt, x_est, 1, params.w_xy_reset_v); - inertial_filter_correct(-y_est[1], dt, y_est, 1, params.w_xy_reset_v); + inertial_filter_correct(-x_est[1], dt, x_est, 1, params.w_xy_res_v); + inertial_filter_correct(-y_est[1], dt, y_est, 1, params.w_xy_res_v); } /* detect land */ diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c index b79e00274..47c1a4c6c 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c @@ -46,7 +46,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f); -PARAM_DEFINE_FLOAT(INAV_W_XY_RESET_V, 0.2f); +PARAM_DEFINE_FLOAT(INAV_W_XY_RES_V, 0.2f); PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f); PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f); PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.15f); @@ -66,7 +66,7 @@ int parameters_init(struct position_estimator_inav_param_handles *h) h->w_xy_gps_p = param_find("INAV_W_XY_GPS_P"); h->w_xy_gps_v = param_find("INAV_W_XY_GPS_V"); h->w_xy_flow = param_find("INAV_W_XY_FLOW"); - h->w_xy_reset_v = param_find("INAV_W_XY_RESET_V"); + h->w_xy_res_v = param_find("INAV_W_XY_RES_V"); h->w_gps_flow = param_find("INAV_W_GPS_FLOW"); h->w_acc_bias = param_find("INAV_W_ACC_BIAS"); h->flow_k = param_find("INAV_FLOW_K"); @@ -89,7 +89,7 @@ int parameters_update(const struct position_estimator_inav_param_handles *h, str param_get(h->w_xy_gps_p, &(p->w_xy_gps_p)); param_get(h->w_xy_gps_v, &(p->w_xy_gps_v)); param_get(h->w_xy_flow, &(p->w_xy_flow)); - param_get(h->w_xy_reset_v, &(p->w_xy_reset_v)); + param_get(h->w_xy_res_v, &(p->w_xy_res_v)); param_get(h->w_gps_flow, &(p->w_gps_flow)); param_get(h->w_acc_bias, &(p->w_acc_bias)); param_get(h->flow_k, &(p->flow_k)); diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.h b/src/modules/position_estimator_inav/position_estimator_inav_params.h index 9be13637d..423f0d879 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.h +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.h @@ -47,7 +47,7 @@ struct position_estimator_inav_params { float w_xy_gps_p; float w_xy_gps_v; float w_xy_flow; - float w_xy_reset_v; + float w_xy_res_v; float w_gps_flow; float w_acc_bias; float flow_k; @@ -67,7 +67,7 @@ struct position_estimator_inav_param_handles { param_t w_xy_gps_p; param_t w_xy_gps_v; param_t w_xy_flow; - param_t w_xy_reset_v; + param_t w_xy_res_v; param_t w_gps_flow; param_t w_acc_bias; param_t flow_k; -- cgit v1.2.3 From 7a45888e78b4af0c04014c20e579797b2040edf8 Mon Sep 17 00:00:00 2001 From: Antonio Sanniravong Date: Tue, 24 Jun 2014 17:56:36 -0400 Subject: Adjusted default reset param value to reset quicker --- src/modules/position_estimator_inav/position_estimator_inav_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c index 47c1a4c6c..0581f8236 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c @@ -46,7 +46,7 @@ PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f); PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f); -PARAM_DEFINE_FLOAT(INAV_W_XY_RES_V, 0.2f); +PARAM_DEFINE_FLOAT(INAV_W_XY_RES_V, 0.5f); PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f); PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f); PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.15f); -- cgit v1.2.3 From 5330ffe458bd32bcf0e733c93fa2e659fbaaeeb3 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 21 Jun 2014 12:24:37 +0200 Subject: commander: detect if offboard control is lost and missing offboard states --- src/modules/commander/commander.cpp | 14 ++++++++++++++ src/modules/commander/state_machine_helper.cpp | 19 +++++++++++++++++++ 2 files changed, 33 insertions(+) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index fab80e325..0c9ce4418 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -661,6 +661,7 @@ int commander_thread_main(int argc, char *argv[]) nav_states_str[NAVIGATION_STATE_LAND] = "LAND"; nav_states_str[NAVIGATION_STATE_DESCEND] = "DESCEND"; nav_states_str[NAVIGATION_STATE_TERMINATION] = "TERMINATION"; + nav_states_str[NAVIGATION_STATE_OFFBOARD] = "OFFBOARD"; /* pthread for slow low prio thread */ pthread_t commander_low_prio_thread; @@ -932,6 +933,19 @@ int commander_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard); } + if (sp_offboard.timestamp != 0 && + sp_offboard.timestamp + OFFBOARD_TIMEOUT > hrt_absolute_time()) { + if (status.offboard_control_signal_lost) { + status.offboard_control_signal_lost = false; + status_changed = true; + } + } else { + if (!status.offboard_control_signal_lost) { + status.offboard_control_signal_lost = true; + status_changed = true; + } + } + orb_check(telemetry_sub, &updated); if (updated) { diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 81b489ce3..4339a7a76 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -541,6 +541,25 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en } break; + case MAIN_STATE_OFFBOARD: + /* require offboard control, otherwise stay where you are */ + if (status->offboard_control_signal_lost && !status->rc_signal_lost) { + status->failsafe = true; + + status->nav_state = NAVIGATION_STATE_POSCTL; + } else if (status->offboard_control_signal_lost && status->rc_signal_lost) { + status->failsafe = true; + + if (status->condition_local_position_valid) { + status->nav_state = NAVIGATION_STATE_LAND; + } else if (status->condition_local_altitude_valid) { + status->nav_state = NAVIGATION_STATE_DESCEND; + } else { + status->nav_state = NAVIGATION_STATE_TERMINATION; + } + } else { + status->nav_state = NAVIGATION_STATE_OFFBOARD; + } default: break; } -- cgit v1.2.3 From c99683752ccb62c9654b390c8761337f291c58e9 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 21 Jun 2014 12:25:11 +0200 Subject: navigator: added missing offboard state --- src/modules/navigator/navigator_main.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index d762b8a9d..8ab50f0e1 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -363,6 +363,7 @@ Navigator::task_main() break; case NAVIGATION_STATE_LAND: case NAVIGATION_STATE_TERMINATION: + case NAVIGATION_STATE_OFFBOARD: default: _navigation_mode = nullptr; _is_in_loiter = false; -- cgit v1.2.3 From f5699e6490a136f4344bfab10b72a9cdd4860569 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 21 Jun 2014 12:27:11 +0200 Subject: mavlink: always copy offboard setpoints, not just when control mode changed, also bugfixes in orb calls --- src/modules/mavlink/mavlink_receiver.cpp | 123 +++++++++++++++---------------- 1 file changed, 61 insertions(+), 62 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 80404a46a..aaae0933e 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -407,11 +407,10 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message /*Temporary hack to use set_quad_swarm_roll_pitch_yaw_thrust msg for position or velocity */ /* Converts INT16 centimeters to float meters */ - offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / 100.0f; - offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / 100.0f; - offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / 100.0f; - offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / 100.0f; - + offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / 1000.0f; + offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / 1000.0f; + offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / 1000.0f; + offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / 1000.0f; } if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) { @@ -434,83 +433,83 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message orb_check(_control_mode_sub, &updated); if (updated) { orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); + } - if (_control_mode.flag_control_offboard_enabled) { - if (_control_mode.flag_control_position_enabled) { - // TODO Use something else then quad_swarm_roll_pitch_yaw_thrust - struct vehicle_local_position_setpoint_s loc_pos_sp; - memset(&loc_pos_sp, 0, sizeof(loc_pos_sp)); - - loc_pos_sp.x = offboard_control_sp.p1; - loc_pos_sp.y = offboard_control_sp.p2; - loc_pos_sp.yaw = offboard_control_sp.p3; - loc_pos_sp.z = -offboard_control_sp.p4; + if (_control_mode.flag_control_offboard_enabled) { + if (_control_mode.flag_control_position_enabled) { + // TODO Use something else then quad_swarm_roll_pitch_yaw_thrust + struct vehicle_local_position_setpoint_s loc_pos_sp; + memset(&loc_pos_sp, 0, sizeof(loc_pos_sp)); - if (_local_pos_sp_pub < 0) { - _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &_local_pos_sp_pub); + loc_pos_sp.x = offboard_control_sp.p1; + loc_pos_sp.y = offboard_control_sp.p2; + loc_pos_sp.yaw = offboard_control_sp.p3; + loc_pos_sp.z = -offboard_control_sp.p4; - } else { - orb_publish(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_pub, &loc_pos_sp); - } + if (_local_pos_sp_pub < 0) { + _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &loc_pos_sp); - } else if (_control_mode.flag_control_velocity_enabled) { - /* velocity control */ - struct vehicle_global_velocity_setpoint_s global_vel_sp; - memset(&global_vel_sp, 0, sizeof(&global_vel_sp)); + } else { + orb_publish(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_pub, &loc_pos_sp); + } - global_vel_sp.vx = offboard_control_sp.p1; - global_vel_sp.vy = offboard_control_sp.p2; - global_vel_sp.vz = offboard_control_sp.p3; + } else if (_control_mode.flag_control_velocity_enabled) { + /* velocity control */ + struct vehicle_global_velocity_setpoint_s global_vel_sp; + memset(&global_vel_sp, 0, sizeof(&global_vel_sp)); - if (_global_vel_sp_pub < 0) { - _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &_global_vel_sp_pub); + global_vel_sp.vx = offboard_control_sp.p1; + global_vel_sp.vy = offboard_control_sp.p2; + global_vel_sp.vz = offboard_control_sp.p3; - } else { - orb_publish(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_pub, &global_vel_sp); - } + if (_global_vel_sp_pub < 0) { + _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &global_vel_sp); - } else if (_control_mode.flag_control_attitude_enabled) { - /* attitude control */ - struct vehicle_attitude_setpoint_s att_sp; - memset(&att_sp, 0, sizeof(att_sp)); + } else { + orb_publish(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_pub, &global_vel_sp); + } - att_sp.roll_body = offboard_control_sp.p1; - att_sp.pitch_body = offboard_control_sp.p2; - att_sp.yaw_body = offboard_control_sp.p3; - att_sp.thrust = offboard_control_sp.p4; + } else if (_control_mode.flag_control_attitude_enabled) { + /* attitude control */ + struct vehicle_attitude_setpoint_s att_sp; + memset(&att_sp, 0, sizeof(att_sp)); - att_sp.timestamp = hrt_absolute_time(); + att_sp.roll_body = offboard_control_sp.p1; + att_sp.pitch_body = offboard_control_sp.p2; + att_sp.yaw_body = offboard_control_sp.p3; + att_sp.thrust = offboard_control_sp.p4; - if (_att_sp_pub < 0) { - _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); + att_sp.timestamp = hrt_absolute_time(); - } else { - orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &att_sp); - } + if (_att_sp_pub < 0) { + _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); - } else if (_control_mode.flag_control_rates_enabled) { - /* rates control */ - struct vehicle_rates_setpoint_s rates_sp; - memset(&rates_sp, 0, sizeof(rates_sp)); + } else { + orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &att_sp); + } - rates_sp.roll = offboard_control_sp.p1; - rates_sp.pitch = offboard_control_sp.p2; - rates_sp.yaw = offboard_control_sp.p3; - rates_sp.thrust = offboard_control_sp.p4; + } else if (_control_mode.flag_control_rates_enabled) { + /* rates control */ + struct vehicle_rates_setpoint_s rates_sp; + memset(&rates_sp, 0, sizeof(rates_sp)); - rates_sp.timestamp = hrt_absolute_time(); + rates_sp.roll = offboard_control_sp.p1; + rates_sp.pitch = offboard_control_sp.p2; + rates_sp.yaw = offboard_control_sp.p3; + rates_sp.thrust = offboard_control_sp.p4; - if (_rates_sp_pub < 0) { - _rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); + rates_sp.timestamp = hrt_absolute_time(); - } else { - orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &rates_sp); - } + if (_rates_sp_pub < 0) { + _rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); } else { - /* direct control */ - // TODO + orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &rates_sp); } + + } else { + /* direct control */ + // TODO } } } -- cgit v1.2.3 From 993e4d41d8165e27f03e51af5b809da6fd3a7509 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 21 Jun 2014 12:27:32 +0200 Subject: sensors: missing param for offboard switch --- src/modules/sensors/sensor_params.c | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 65e2376ce..dad81d8e1 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -790,3 +790,20 @@ PARAM_DEFINE_FLOAT(RC_LOITER_TH, 0.5f); * */ PARAM_DEFINE_FLOAT(RC_ACRO_TH, 0.5f); + + +/** + * Threshold for selecting offboard mode + * + * min:-1 + * max:+1 + * + * 0-1 indicate where in the full channel range the threshold sits + * 0 : min + * 1 : max + * sign indicates polarity of comparison + * positive : true when channel>th + * negative : true when channel Date: Sat, 21 Jun 2014 12:28:08 +0200 Subject: mc_pos_control: added missing subscribe --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index a4c871d95..e020b2224 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -134,7 +134,7 @@ private: struct position_setpoint_triplet_s _pos_sp_triplet; /**< vehicle global position setpoint triplet */ struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position setpoint */ struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */ - + struct { param_t thr_min; @@ -533,6 +533,8 @@ MulticopterPositionControl::task_main() _local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position)); _pos_sp_triplet_sub = orb_subscribe(ORB_ID(position_setpoint_triplet)); _local_pos_sp_sub = orb_subscribe(ORB_ID(vehicle_local_position_setpoint)); + _global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint)); + parameters_update(true); @@ -699,7 +701,7 @@ MulticopterPositionControl::task_main() reset_pos_sp(); reset_alt_sp(); } - + } else { /* AUTO */ bool updated; -- cgit v1.2.3 From 7992a063c9f9b2cf7fbb49dcd5d19c60f15d0bfc Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 27 Jun 2014 10:34:34 +0200 Subject: navigator: added offboard mode --- src/modules/navigator/module.mk | 1 + src/modules/navigator/navigator.h | 8 +- src/modules/navigator/navigator_main.cpp | 7 ++ src/modules/navigator/offboard.cpp | 124 +++++++++++++++++++++++++++++++ src/modules/navigator/offboard.h | 82 ++++++++++++++++++++ 5 files changed, 221 insertions(+), 1 deletion(-) create mode 100644 src/modules/navigator/offboard.cpp create mode 100644 src/modules/navigator/offboard.h diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk index a1e109030..637eaae59 100644 --- a/src/modules/navigator/module.mk +++ b/src/modules/navigator/module.mk @@ -46,6 +46,7 @@ SRCS = navigator_main.cpp \ loiter.cpp \ rtl.cpp \ rtl_params.c \ + offboard.cpp \ mission_feasibility_checker.cpp \ geofence.cpp \ geofence_params.c diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index dadd15527..e6ff213bd 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -56,13 +56,14 @@ #include "mission.h" #include "loiter.h" #include "rtl.h" +#include "offboard.h" #include "geofence.h" /** * Number of navigation modes that need on_active/on_inactive calls * Currently: mission, loiter, and rtl */ -#define NAVIGATOR_MODE_ARRAY_SIZE 3 +#define NAVIGATOR_MODE_ARRAY_SIZE 4 class Navigator : public control::SuperBlock { @@ -108,10 +109,13 @@ public: * Getters */ struct vehicle_status_s* get_vstatus() { return &_vstatus; } + struct vehicle_control_mode_s* get_control_mode() { return &_control_mode; } struct vehicle_global_position_s* get_global_position() { return &_global_pos; } struct home_position_s* get_home_position() { return &_home_pos; } + int get_onboard_mission_sub() { return _onboard_mission_sub; } int get_offboard_mission_sub() { return _offboard_mission_sub; } + int get_offboard_control_sp_sub() { return _offboard_control_sp_sub; } Geofence& get_geofence() { return _geofence; } bool get_is_in_loiter() { return _is_in_loiter; } float get_loiter_radius() { return _param_loiter_radius.get(); } @@ -129,6 +133,7 @@ private: int _home_pos_sub; /**< home position subscription */ int _vstatus_sub; /**< vehicle status subscription */ int _capabilities_sub; /**< notification of vehicle capabilities updates */ + int _offboard_control_sp_sub; /*** offboard control subscription */ int _control_mode_sub; /**< vehicle control mode subscription */ int _onboard_mission_sub; /**< onboard mission subscription */ int _offboard_mission_sub; /**< offboard mission subscription */ @@ -158,6 +163,7 @@ private: Mission _mission; /**< class that handles the missions */ Loiter _loiter; /**< class that handles loiter */ RTL _rtl; /**< class that handles RTL */ + Offboard _offboard; /**< class that handles offboard */ NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]; /**< array of navigation modes */ diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 8ab50f0e1..8ba835a87 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -67,6 +67,7 @@ #include #include #include +#include #include #include @@ -100,6 +101,7 @@ Navigator::Navigator() : _home_pos_sub(-1), _vstatus_sub(-1), _capabilities_sub(-1), + _offboard_control_sp_sub(-1), _control_mode_sub(-1), _onboard_mission_sub(-1), _offboard_mission_sub(-1), @@ -121,6 +123,7 @@ Navigator::Navigator() : _mission(this, "MIS"), _loiter(this, "LOI"), _rtl(this, "RTL"), + _offboard(this, "OFF"), _update_triplet(false), _param_loiter_radius(this, "LOITER_RAD"), _param_takeoff_acceptance_radius(this, "TF_ACC_RAD") @@ -129,6 +132,7 @@ Navigator::Navigator() : _navigation_mode_array[0] = &_mission; _navigation_mode_array[1] = &_loiter; _navigation_mode_array[2] = &_rtl; + _navigation_mode_array[3] = &_offboard; updateParams(); } @@ -241,6 +245,7 @@ Navigator::task_main() _onboard_mission_sub = orb_subscribe(ORB_ID(onboard_mission)); _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission)); _param_update_sub = orb_subscribe(ORB_ID(parameter_update)); + _offboard_control_sp_sub = orb_subscribe(ORB_ID(offboard_control_setpoint)); /* copy all topics first time */ vehicle_status_update(); @@ -364,6 +369,8 @@ Navigator::task_main() case NAVIGATION_STATE_LAND: case NAVIGATION_STATE_TERMINATION: case NAVIGATION_STATE_OFFBOARD: + _navigation_mode = &_offboard; + break; default: _navigation_mode = nullptr; _is_in_loiter = false; diff --git a/src/modules/navigator/offboard.cpp b/src/modules/navigator/offboard.cpp new file mode 100644 index 000000000..b0cbb1aa1 --- /dev/null +++ b/src/modules/navigator/offboard.cpp @@ -0,0 +1,124 @@ +/**************************************************************************** + * + * Copyright (c) 2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +/** + * @file offboard.cpp + * + * Helper class for offboard commands + * + * @author Julian Oes + */ + +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include "navigator.h" +#include "offboard.h" + +Offboard::Offboard(Navigator *navigator, const char *name) : + NavigatorMode(navigator, name), + _offboard_control_sp({0}) +{ + /* load initial params */ + updateParams(); + /* initial reset */ + on_inactive(); +} + +Offboard::~Offboard() +{ +} + +bool +Offboard::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) +{ + bool updated; + orb_check(_navigator->get_offboard_control_sp_sub(), &updated); + if (updated) { + update_offboard_control_setpoint(); + } + + bool changed = false; + + /* copy offboard setpoints to the corresponding topics */ + if (_navigator->get_control_mode()->flag_control_position_enabled + && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) { + /* position control */ + pos_sp_triplet->current.x = _offboard_control_sp.p1; + pos_sp_triplet->current.y = _offboard_control_sp.p2; + pos_sp_triplet->current.yaw = _offboard_control_sp.p3; + pos_sp_triplet->current.z = -_offboard_control_sp.p4; + + pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD; + pos_sp_triplet->current.valid = true; + pos_sp_triplet->current.position_valid = true; + + changed = true; + + } else if (_navigator->get_control_mode()->flag_control_velocity_enabled + && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY) { + /* velocity control */ + pos_sp_triplet->current.vx = _offboard_control_sp.p2; + pos_sp_triplet->current.vy = _offboard_control_sp.p1; + pos_sp_triplet->current.yawspeed = _offboard_control_sp.p3*10.0f; + pos_sp_triplet->current.vz = _offboard_control_sp.p4; + + pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD; + pos_sp_triplet->current.valid = true; + pos_sp_triplet->current.velocity_valid = true; + + changed = true; + } + + return changed; +} + +void +Offboard::on_inactive() +{ +} + +void +Offboard::update_offboard_control_setpoint() +{ + orb_copy(ORB_ID(offboard_control_setpoint), _navigator->get_offboard_control_sp_sub(), &_offboard_control_sp); + +} diff --git a/src/modules/navigator/offboard.h b/src/modules/navigator/offboard.h new file mode 100644 index 000000000..4d415dddb --- /dev/null +++ b/src/modules/navigator/offboard.h @@ -0,0 +1,82 @@ +/*************************************************************************** + * + * Copyright (c) 2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ +/** + * @file offboard.h + * + * Helper class for offboard commands + * + * @author Julian Oes + */ + +#ifndef NAVIGATOR_OFFBOARD_H +#define NAVIGATOR_OFFBOARD_H + +#include +#include + +#include +#include + +#include "navigator_mode.h" + +class Navigator; + +class Offboard : public NavigatorMode +{ +public: + /** + * Constructor + */ + Offboard(Navigator *navigator, const char *name); + + /** + * Destructor + */ + ~Offboard(); + + /** + * This function is called while the mode is inactive + */ + virtual void on_inactive(); + + /** + * This function is called while the mode is active + */ + virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet); +private: + void update_offboard_control_setpoint(); + + struct offboard_control_setpoint_s _offboard_control_sp; +}; + +#endif -- cgit v1.2.3 From a122e88893f4b983a6e8e2e2838f9a16f055c8d1 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 27 Jun 2014 10:35:02 +0200 Subject: commander: hack to get velocity offboard control working --- src/modules/commander/commander.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 0c9ce4418..e4d132c40 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1776,9 +1776,9 @@ set_control_mode() case OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY: control_mode.flag_control_rates_enabled = true; control_mode.flag_control_attitude_enabled = true; - control_mode.flag_control_altitude_enabled = false; + control_mode.flag_control_altitude_enabled = true; /* XXX: hack for now */ control_mode.flag_control_climb_rate_enabled = true; - control_mode.flag_control_position_enabled = false; + control_mode.flag_control_position_enabled = true; /* XXX: hack for now */ control_mode.flag_control_velocity_enabled = true; break; case OFFBOARD_CONTROL_MODE_DIRECT_POSITION: -- cgit v1.2.3 From 4c4d14347efe9d12712399a1a5eb0140fdd113fd Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 27 Jun 2014 10:43:29 +0200 Subject: mavlink: only save a offboard_control, don't publish to setpoint topics (let the navigator do this) --- src/modules/mavlink/mavlink_receiver.cpp | 154 +++---------------------------- 1 file changed, 11 insertions(+), 143 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index aaae0933e..c4955f1b3 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -355,70 +355,22 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg) void MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg) { - mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t quad_motors_setpoint; - mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &quad_motors_setpoint); + mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t swarm_offboard_control; + mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &swarm_offboard_control); - if (mavlink_system.sysid < 4) { + /* Only accept system IDs from 1 to 4 + * TODO: check for own system ID */ + if (mavlink_system.sysid >= 1 && mavlink_system.sysid <= 4) { struct offboard_control_setpoint_s offboard_control_sp; memset(&offboard_control_sp, 0, sizeof(offboard_control_sp)); - enum OFFBOARD_CONTROL_MODE ml_mode = OFFBOARD_CONTROL_MODE_DIRECT; - bool ml_armed = false; + /* Convert values * 1000 back */ + offboard_control_sp.p1 = (float)swarm_offboard_control.roll[mavlink_system.sysid - 1] / 1000.0f; + offboard_control_sp.p2 = (float)swarm_offboard_control.pitch[mavlink_system.sysid - 1] / 1000.0f; + offboard_control_sp.p3 = (float)swarm_offboard_control.yaw[mavlink_system.sysid - 1] / 1000.0f; + offboard_control_sp.p4 = (float)swarm_offboard_control.thrust[mavlink_system.sysid - 1] / 1000.0f; - switch (quad_motors_setpoint.mode) { - case 0: - break; - - case 1: - ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_RATES; - ml_armed = true; - - break; - - case 2: - ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE; - ml_armed = true; - - break; - - case 3: - ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY; - ml_armed = true; - - break; - - case 4: - ml_mode = OFFBOARD_CONTROL_MODE_DIRECT_POSITION; - ml_armed = true; - - break; - default: - break; - } - - if (ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_RATES || ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_ATTITUDE) { - - offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / (float)INT16_MAX; - offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / (float)INT16_MAX; - offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / (float)INT16_MAX; - offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / (float)UINT16_MAX; - - } else if (ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY || ml_mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) { - - /*Temporary hack to use set_quad_swarm_roll_pitch_yaw_thrust msg for position or velocity */ - /* Converts INT16 centimeters to float meters */ - offboard_control_sp.p1 = (float)quad_motors_setpoint.roll[mavlink_system.sysid - 1] / 1000.0f; - offboard_control_sp.p2 = (float)quad_motors_setpoint.pitch[mavlink_system.sysid - 1] / 1000.0f; - offboard_control_sp.p3 = (float)quad_motors_setpoint.yaw[mavlink_system.sysid - 1] / 1000.0f; - offboard_control_sp.p4 = (float)quad_motors_setpoint.thrust[mavlink_system.sysid - 1] / 1000.0f; - } - - if (quad_motors_setpoint.thrust[mavlink_system.sysid - 1] == 0) { - ml_armed = false; - } - - offboard_control_sp.armed = ml_armed; - offboard_control_sp.mode = ml_mode; + offboard_control_sp.mode = (enum OFFBOARD_CONTROL_MODE)swarm_offboard_control.mode; offboard_control_sp.timestamp = hrt_absolute_time(); @@ -428,90 +380,6 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message } else { orb_publish(ORB_ID(offboard_control_setpoint), _offboard_control_sp_pub, &offboard_control_sp); } - - bool updated; - orb_check(_control_mode_sub, &updated); - if (updated) { - orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); - } - - if (_control_mode.flag_control_offboard_enabled) { - if (_control_mode.flag_control_position_enabled) { - // TODO Use something else then quad_swarm_roll_pitch_yaw_thrust - struct vehicle_local_position_setpoint_s loc_pos_sp; - memset(&loc_pos_sp, 0, sizeof(loc_pos_sp)); - - loc_pos_sp.x = offboard_control_sp.p1; - loc_pos_sp.y = offboard_control_sp.p2; - loc_pos_sp.yaw = offboard_control_sp.p3; - loc_pos_sp.z = -offboard_control_sp.p4; - - if (_local_pos_sp_pub < 0) { - _local_pos_sp_pub = orb_advertise(ORB_ID(vehicle_local_position_setpoint), &loc_pos_sp); - - } else { - orb_publish(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_pub, &loc_pos_sp); - } - - } else if (_control_mode.flag_control_velocity_enabled) { - /* velocity control */ - struct vehicle_global_velocity_setpoint_s global_vel_sp; - memset(&global_vel_sp, 0, sizeof(&global_vel_sp)); - - global_vel_sp.vx = offboard_control_sp.p1; - global_vel_sp.vy = offboard_control_sp.p2; - global_vel_sp.vz = offboard_control_sp.p3; - - if (_global_vel_sp_pub < 0) { - _global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &global_vel_sp); - - } else { - orb_publish(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_pub, &global_vel_sp); - } - - } else if (_control_mode.flag_control_attitude_enabled) { - /* attitude control */ - struct vehicle_attitude_setpoint_s att_sp; - memset(&att_sp, 0, sizeof(att_sp)); - - att_sp.roll_body = offboard_control_sp.p1; - att_sp.pitch_body = offboard_control_sp.p2; - att_sp.yaw_body = offboard_control_sp.p3; - att_sp.thrust = offboard_control_sp.p4; - - att_sp.timestamp = hrt_absolute_time(); - - if (_att_sp_pub < 0) { - _att_sp_pub = orb_advertise(ORB_ID(vehicle_attitude_setpoint), &att_sp); - - } else { - orb_publish(ORB_ID(vehicle_attitude_setpoint), _att_sp_pub, &att_sp); - } - - } else if (_control_mode.flag_control_rates_enabled) { - /* rates control */ - struct vehicle_rates_setpoint_s rates_sp; - memset(&rates_sp, 0, sizeof(rates_sp)); - - rates_sp.roll = offboard_control_sp.p1; - rates_sp.pitch = offboard_control_sp.p2; - rates_sp.yaw = offboard_control_sp.p3; - rates_sp.thrust = offboard_control_sp.p4; - - rates_sp.timestamp = hrt_absolute_time(); - - if (_rates_sp_pub < 0) { - _rates_sp_pub = orb_advertise(ORB_ID(vehicle_rates_setpoint), &rates_sp); - - } else { - orb_publish(ORB_ID(vehicle_rates_setpoint), _rates_sp_pub, &rates_sp); - } - - } else { - /* direct control */ - // TODO - } - } } } -- cgit v1.2.3 From df9381636a2fa96e1bc02b4244273ec6b7f11aa9 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 27 Jun 2014 10:44:05 +0200 Subject: offboard_control_setpoint: armed does not make sense there --- src/modules/uORB/topics/offboard_control_setpoint.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uORB/topics/offboard_control_setpoint.h b/src/modules/uORB/topics/offboard_control_setpoint.h index 68d3e494b..d7b131e3c 100644 --- a/src/modules/uORB/topics/offboard_control_setpoint.h +++ b/src/modules/uORB/topics/offboard_control_setpoint.h @@ -69,7 +69,7 @@ struct offboard_control_setpoint_s { uint64_t timestamp; enum OFFBOARD_CONTROL_MODE mode; /**< The current control inputs mode */ - bool armed; /**< Armed flag set, yes / no */ + float p1; /**< ailerons roll / roll rate input */ float p2; /**< elevator / pitch / pitch rate */ float p3; /**< rudder / yaw rate / yaw */ -- cgit v1.2.3 From 0b172d662a8926dbe1c8a0c59766f7c63bb8f4fe Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 27 Jun 2014 10:44:38 +0200 Subject: position_setpoint_triplet: add local position and velocity setpoints --- src/modules/uORB/topics/position_setpoint_triplet.h | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h index ce42035ba..673c0e491 100644 --- a/src/modules/uORB/topics/position_setpoint_triplet.h +++ b/src/modules/uORB/topics/position_setpoint_triplet.h @@ -60,16 +60,26 @@ enum SETPOINT_TYPE SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */ SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, descend until landing */ SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */ + SETPOINT_TYPE_OFFBOARD, /**< setpoint set by offboard */ }; struct position_setpoint_s { bool valid; /**< true if setpoint is valid */ enum SETPOINT_TYPE type; /**< setpoint type to adjust behavior of position controller */ + float x; /**< local position setpoint in m in NED */ + float y; /**< local position setpoint in m in NED */ + float z; /**< local position setpoint in m in NED */ + bool position_valid; /**< true if local position setpoint valid */ + float vx; /**< local velocity setpoint in m in NED */ + float vy; /**< local velocity setpoint in m in NED */ + float vz; /**< local velocity setpoint in m in NED */ + bool velocity_valid; /**< true if local velocity setpoint valid */ double lat; /**< latitude, in deg */ double lon; /**< longitude, in deg */ float alt; /**< altitude AMSL, in m */ float yaw; /**< yaw (only for multirotors), in rad [-PI..PI), NaN = hold current yaw */ + float yawspeed; /**< yawspeed (only for multirotors, in rad/s) */ float loiter_radius; /**< loiter radius (only for fixed wing), in m */ int8_t loiter_direction; /**< loiter direction: 1 = CW, -1 = CCW */ float pitch_min; /**< minimal pitch angle for fixed wing takeoff waypoints */ -- cgit v1.2.3 From ee872d91b05bf47d44dae4f5cc07be1631db91c1 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 27 Jun 2014 10:45:48 +0200 Subject: mc_pos_control: read velocity setpoints form offboard control and do position offset control --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 88 +++++++++++++++------- 1 file changed, 59 insertions(+), 29 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index e020b2224..6541788f6 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -556,6 +556,9 @@ MulticopterPositionControl::task_main() math::Vector<3> sp_move_rate; sp_move_rate.zero(); + + float yaw_sp_move_rate; + math::Vector<3> thrust_int; thrust_int.zero(); math::Matrix<3, 3> R; @@ -674,28 +677,73 @@ MulticopterPositionControl::task_main() } else if (_control_mode.flag_control_offboard_enabled) { /* Offboard control */ bool updated; - orb_check(_local_pos_sp_sub, &updated); + orb_check(_pos_sp_triplet_sub, &updated); if (updated) { - orb_copy(ORB_ID(vehicle_local_position_setpoint), _local_pos_sp_sub, &_local_pos_sp); + orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet); } - if (isfinite(_local_pos_sp.x) && isfinite(_local_pos_sp.y) && isfinite(_local_pos_sp.z) && isfinite(_local_pos_sp.yaw)) { - /* If manual control overides offboard, cancel the offboard setpoint and stay at current position */ - _reset_pos_sp = true; - _reset_alt_sp = true; + if (_pos_sp_triplet.current.valid) { + + if (_control_mode.flag_control_position_enabled && _pos_sp_triplet.current.position_valid) { + + _pos_sp(0) = _pos_sp_triplet.current.x; + _pos_sp(1) = _pos_sp_triplet.current.y; + _pos_sp(2) = _pos_sp_triplet.current.z; + _att_sp.yaw_body = _pos_sp_triplet.current.yaw; + + } else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) { + /* reset position setpoint to current position if needed */ + reset_pos_sp(); + /* move position setpoint with roll/pitch stick */ + sp_move_rate(0) = _pos_sp_triplet.current.vx; + sp_move_rate(1) = _pos_sp_triplet.current.vy; + yaw_sp_move_rate = _pos_sp_triplet.current.yawspeed; + _att_sp.yaw_body = _att.yaw + yaw_sp_move_rate * dt; + } + + if (_control_mode.flag_control_altitude_enabled) { + /* reset alt setpoint to current altitude if needed */ + reset_alt_sp(); + + /* move altitude setpoint with throttle stick */ + sp_move_rate(2) = -scale_control(_pos_sp_triplet.current.vz - 0.5f, 0.5f, alt_ctl_dz);; + } + + /* limit setpoint move rate */ + float sp_move_norm = sp_move_rate.length(); + + if (sp_move_norm > 1.0f) { + sp_move_rate /= sp_move_norm; + } + + /* scale to max speed and rotate around yaw */ + math::Matrix<3, 3> R_yaw_sp; + R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body); + sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max); + + /* move position setpoint */ + _pos_sp += sp_move_rate * dt; + + /* check if position setpoint is too far from actual position */ + math::Vector<3> pos_sp_offs; + pos_sp_offs.zero(); - /* Make sure position control is selected i.e. not only velocity control */ if (_control_mode.flag_control_position_enabled) { - _pos_sp(0) = _local_pos_sp.x; - _pos_sp(1) = _local_pos_sp.y; + pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0); + pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1); } if (_control_mode.flag_control_altitude_enabled) { - _pos_sp(2) = _local_pos_sp.z; + pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2); } - _att_sp.yaw_body = _local_pos_sp.yaw; + float pos_sp_offs_norm = pos_sp_offs.length(); + + if (pos_sp_offs_norm > 1.0f) { + pos_sp_offs /= pos_sp_offs_norm; + _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max); + } } else { reset_pos_sp(); @@ -792,24 +840,6 @@ MulticopterPositionControl::task_main() _vel_sp(2) = _params.land_speed; } - /* Offboard velocity control mode */ - if (_control_mode.flag_control_offboard_enabled) { - bool updated; - orb_check(_global_vel_sp_sub, &updated); - - if (updated) { - orb_copy(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_sub, &_global_vel_sp); - } - - if (!_control_mode.flag_control_altitude_enabled && _control_mode.flag_control_climb_rate_enabled) { - _vel_sp(2) = _global_vel_sp.vz; - } - - if (!_control_mode.flag_control_position_enabled && _control_mode.flag_control_velocity_enabled) { - _vel_sp(0) = _global_vel_sp.vx; - _vel_sp(1) = _global_vel_sp.vy; - } - } if (!_control_mode.flag_control_manual_enabled) { /* limit 3D speed only in non-manual modes */ -- cgit v1.2.3 From 93887f9f28d978290e6698b7f2b7e1e9b60bec13 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 27 Jun 2014 14:04:50 +0200 Subject: navigator: remove hacked scale factor for offboard control --- src/modules/navigator/offboard.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/offboard.cpp b/src/modules/navigator/offboard.cpp index b0cbb1aa1..ef7d11a03 100644 --- a/src/modules/navigator/offboard.cpp +++ b/src/modules/navigator/offboard.cpp @@ -98,7 +98,7 @@ Offboard::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) /* velocity control */ pos_sp_triplet->current.vx = _offboard_control_sp.p2; pos_sp_triplet->current.vy = _offboard_control_sp.p1; - pos_sp_triplet->current.yawspeed = _offboard_control_sp.p3*10.0f; + pos_sp_triplet->current.yawspeed = _offboard_control_sp.p3; pos_sp_triplet->current.vz = _offboard_control_sp.p4; pos_sp_triplet->current.type = SETPOINT_TYPE_OFFBOARD; -- cgit v1.2.3 From ee6e0000980f2127913dfec73b1981b559f85877 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 27 Jun 2014 14:08:13 +0200 Subject: mavlink: fix comment in swarm message receiver --- src/modules/mavlink/mavlink_receiver.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index c4955f1b3..c96bd9273 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -358,8 +358,7 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t swarm_offboard_control; mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &swarm_offboard_control); - /* Only accept system IDs from 1 to 4 - * TODO: check for own system ID */ + /* Only accept system IDs from 1 to 4 */ if (mavlink_system.sysid >= 1 && mavlink_system.sysid <= 4) { struct offboard_control_setpoint_s offboard_control_sp; memset(&offboard_control_sp, 0, sizeof(offboard_control_sp)); -- cgit v1.2.3 From 456e628e129b446d18246ab8ad312a15beea5996 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 28 Jun 2014 00:54:27 +0200 Subject: navigator: NavigatorMode and MissionBlock API cleanup --- src/modules/navigator/loiter.cpp | 18 ++++++--- src/modules/navigator/loiter.h | 14 +------ src/modules/navigator/mission.cpp | 14 +++++-- src/modules/navigator/mission.h | 14 +------ src/modules/navigator/mission_block.cpp | 65 ++++++++++++++++++-------------- src/modules/navigator/mission_block.h | 14 +++---- src/modules/navigator/navigator_main.cpp | 6 +-- src/modules/navigator/navigator_mode.cpp | 34 +++++++++++++++-- src/modules/navigator/navigator_mode.h | 12 +++++- src/modules/navigator/rtl.cpp | 62 ++++++++++++++---------------- src/modules/navigator/rtl.h | 20 ++-------- 11 files changed, 144 insertions(+), 129 deletions(-) diff --git a/src/modules/navigator/loiter.cpp b/src/modules/navigator/loiter.cpp index 542483fb1..5e7067b0e 100644 --- a/src/modules/navigator/loiter.cpp +++ b/src/modules/navigator/loiter.cpp @@ -65,14 +65,22 @@ Loiter::~Loiter() { } -bool -Loiter::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) +void +Loiter::on_inactive() { - /* set loiter item, don't reuse an existing position setpoint */ - return set_loiter_item(pos_sp_triplet); } void -Loiter::on_inactive() +Loiter::on_activation(struct position_setpoint_triplet_s *pos_sp_triplet) +{ + set_loiter_item(pos_sp_triplet); + pos_sp_triplet->previous.valid = false; + mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); + pos_sp_triplet->next.valid = false; +} + +bool +Loiter::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) { + return false; } diff --git a/src/modules/navigator/loiter.h b/src/modules/navigator/loiter.h index 65ff5c31e..5ce86d2a7 100644 --- a/src/modules/navigator/loiter.h +++ b/src/modules/navigator/loiter.h @@ -50,24 +50,14 @@ class Loiter : public MissionBlock { public: - /** - * Constructor - */ Loiter(Navigator *navigator, const char *name); - /** - * Destructor - */ ~Loiter(); - /** - * This function is called while the mode is inactive - */ virtual void on_inactive(); - /** - * This function is called while the mode is active - */ + virtual void on_activation(struct position_setpoint_triplet_s *pos_sp_triplet); + virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet); }; diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 72255103b..395669698 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -82,8 +82,6 @@ Mission::~Mission() void Mission::on_inactive() { - _first_run = true; - /* check anyway if missions have changed so that feedback to groundstation is given */ bool onboard_updated; orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated); @@ -98,6 +96,12 @@ Mission::on_inactive() } } +void +Mission::on_activation(struct position_setpoint_triplet_s *pos_sp_triplet) +{ + set_mission_items(pos_sp_triplet); +} + bool Mission::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) { @@ -117,10 +121,9 @@ Mission::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) } /* reset mission items if needed */ - if (onboard_updated || offboard_updated || _first_run) { + if (onboard_updated || offboard_updated) { set_mission_items(pos_sp_triplet); updated = true; - _first_run = false; } /* lets check if we reached the current mission item */ @@ -255,6 +258,9 @@ Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet) _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached); set_loiter_item(pos_sp_triplet); + pos_sp_triplet->previous.valid = false; + mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); + pos_sp_triplet->next.valid = false; reset_mission_item_reached(); report_mission_finished(); } diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index 6e4761946..38a4f7612 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -65,24 +65,14 @@ class Navigator; class Mission : public MissionBlock { public: - /** - * Constructor - */ Mission(Navigator *navigator, const char *name); - /** - * Destructor - */ virtual ~Mission(); - /** - * This function is called while the mode is inactive - */ virtual void on_inactive(); - /** - * This function is called while the mode is active - */ + virtual void on_activation(struct position_setpoint_triplet_s *pos_sp_triplet); + virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet); private: diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index 9b8d3d9c7..acf3ad569 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -45,6 +45,7 @@ #include #include +#include #include @@ -207,36 +208,44 @@ MissionBlock::set_previous_pos_setpoint(struct position_setpoint_triplet_s *pos_ } } -bool +void MissionBlock::set_loiter_item(struct position_setpoint_triplet_s *pos_sp_triplet) { - /* don't change setpoint if 'can_loiter_at_sp' flag set */ - if (!(_navigator->get_can_loiter_at_sp() && pos_sp_triplet->current.valid)) { - /* use current position */ - pos_sp_triplet->current.lat = _navigator->get_global_position()->lat; - pos_sp_triplet->current.lon = _navigator->get_global_position()->lon; - pos_sp_triplet->current.alt = _navigator->get_global_position()->alt; - pos_sp_triplet->current.yaw = NAN; /* NAN means to use current yaw */ - - _navigator->set_can_loiter_at_sp(true); - } + if (_navigator->get_vstatus()->condition_landed) { + /* landed, don't takeoff, but switch to IDLE mode */ + _mission_item.nav_cmd = NAV_CMD_IDLE; - if (pos_sp_triplet->current.type != SETPOINT_TYPE_LOITER - || pos_sp_triplet->current.loiter_radius != _navigator->get_loiter_radius() - || pos_sp_triplet->current.loiter_direction != 1 - || pos_sp_triplet->previous.valid - || !pos_sp_triplet->current.valid - || pos_sp_triplet->next.valid) { - /* position setpoint triplet should be updated */ - pos_sp_triplet->current.type = SETPOINT_TYPE_LOITER; - pos_sp_triplet->current.loiter_radius = _navigator->get_loiter_radius(); - pos_sp_triplet->current.loiter_direction = 1; - - pos_sp_triplet->previous.valid = false; - pos_sp_triplet->current.valid = true; - pos_sp_triplet->next.valid = false; - return true; - } + _navigator->set_can_loiter_at_sp(false); + + mavlink_log_info(_navigator->get_mavlink_fd(), "landed, switch to IDLE"); + + } else { + _mission_item.nav_cmd = NAV_CMD_LOITER_UNLIMITED; - return false; + if (_navigator->get_can_loiter_at_sp() && pos_sp_triplet->current.valid) { + /* use current position setpoint */ + _mission_item.lat = pos_sp_triplet->current.lat; + _mission_item.lon = pos_sp_triplet->current.lon; + _mission_item.altitude = pos_sp_triplet->current.alt; + + } else { + /* use current position */ + _mission_item.lat = _navigator->get_global_position()->lat; + _mission_item.lon = _navigator->get_global_position()->lon; + _mission_item.altitude = _navigator->get_global_position()->alt; + } + + _mission_item.altitude_is_relative = false; + _mission_item.yaw = NAN; + _mission_item.loiter_radius = _navigator->get_loiter_radius(); + _mission_item.loiter_direction = 1; + _mission_item.acceptance_radius = _navigator->get_acceptance_radius(); + _mission_item.time_inside = 0.0f; + _mission_item.pitch_min = 0.0f; + _mission_item.autocontinue = false; + _mission_item.origin = ORIGIN_ONBOARD; + + _navigator->set_can_loiter_at_sp(true); + mavlink_log_info(_navigator->get_mavlink_fd(), "switch to LOITER"); + } } diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h index f99002752..4f79238f4 100644 --- a/src/modules/navigator/mission_block.h +++ b/src/modules/navigator/mission_block.h @@ -64,6 +64,7 @@ public: */ virtual ~MissionBlock(); +protected: /** * Check if mission item has been reached * @return true if successfully reached @@ -88,19 +89,16 @@ public: void set_previous_pos_setpoint(struct position_setpoint_triplet_s *pos_sp_triplet); /** - * Set a loiter item, if possible reuse the position setpoint, otherwise take the current position - * - * @param the position setpoint triplet to set - * @return true if setpoint has changed + * Set a loiter mission item, if possible reuse the position setpoint, otherwise take the current position */ - bool set_loiter_item(position_setpoint_triplet_s *pos_sp_triplet); + // TODO remove argument, get position setpoint from navigator, add to arguments pointer to mission item instead + void set_loiter_item(struct position_setpoint_triplet_s *pos_sp_triplet); + mission_item_s _mission_item; + bool _mission_item_valid; bool _waypoint_position_reached; bool _waypoint_yaw_reached; hrt_abstime _time_first_inside_orbit; - - mission_item_s _mission_item; - bool _mission_item_valid; }; #endif diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 546602741..266114e38 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -371,11 +371,7 @@ Navigator::task_main() /* iterate through navigation modes and set active/inactive for each */ for(unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) { - if (_navigation_mode == _navigation_mode_array[i]) { - _update_triplet = _navigation_mode_array[i]->on_active(&_pos_sp_triplet); - } else { - _navigation_mode_array[i]->on_inactive(); - } + _update_triplet = _navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i], &_pos_sp_triplet); } /* if nothing is running, set position setpoint triplet invalid */ diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp index 25e767c2b..6361ea9c8 100644 --- a/src/modules/navigator/navigator_mode.cpp +++ b/src/modules/navigator/navigator_mode.cpp @@ -33,9 +33,10 @@ /** * @file navigator_mode.cpp * - * Helper class for different modes in navigator + * Base class for different modes in navigator * * @author Julian Oes + * @author Anton Babushkin */ #include "navigator_mode.h" @@ -55,16 +56,41 @@ NavigatorMode::~NavigatorMode() { } +bool +NavigatorMode::run(bool active, struct position_setpoint_triplet_s *pos_sp_triplet) { + if (active) { + if (_first_run) { + /* first run */ + _first_run = false; + on_activation(pos_sp_triplet); + return true; + + } else { + /* periodic updates when active */ + on_active(pos_sp_triplet); + } + + } else { + /* periodic updates when inactive */ + _first_run = true; + on_inactive(); + } +} + void NavigatorMode::on_inactive() { - _first_run = true; +} + +void +NavigatorMode::on_activation(struct position_setpoint_triplet_s *pos_sp_triplet) +{ + /* invalidate position setpoint by default */ + pos_sp_triplet->current.valid = false; } bool NavigatorMode::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) { - pos_sp_triplet->current.valid = false; - _first_run = false; return false; } diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h index cbb53d91b..5c36af1fe 100644 --- a/src/modules/navigator/navigator_mode.h +++ b/src/modules/navigator/navigator_mode.h @@ -33,9 +33,10 @@ /** * @file navigator_mode.h * - * Helper class for different modes in navigator + * Base class for different modes in navigator * * @author Julian Oes + * @author Anton Babushkin */ #ifndef NAVIGATOR_MODE_H @@ -65,11 +66,18 @@ public: */ virtual ~NavigatorMode(); + bool run(bool active, struct position_setpoint_triplet_s *pos_sp_triplet); + /** * This function is called while the mode is inactive */ virtual void on_inactive(); + /** + * This function is called one time when mode become active, poos_sp_triplet must be initialized here + */ + virtual void on_activation(struct position_setpoint_triplet_s *pos_sp_triplet); + /** * This function is called while the mode is active * @@ -80,6 +88,8 @@ public: protected: Navigator *_navigator; + +private: bool _first_run; }; diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp index 043f773a4..7cf6bb1a8 100644 --- a/src/modules/navigator/rtl.cpp +++ b/src/modules/navigator/rtl.cpp @@ -75,53 +75,49 @@ RTL::~RTL() void RTL::on_inactive() { - _first_run = true; - /* reset RTL state only if setpoint moved */ if (!_navigator->get_can_loiter_at_sp()) { _rtl_state = RTL_STATE_NONE; } } -bool -RTL::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) +void +RTL::on_activation(struct position_setpoint_triplet_s *pos_sp_triplet) { - bool updated = false; - - if (_first_run) { - _first_run = false; - - /* decide where to enter the RTL procedure when we switch into it */ - if (_rtl_state == RTL_STATE_NONE) { - /* for safety reasons don't go into RTL if landed */ - if (_navigator->get_vstatus()->condition_landed) { - _rtl_state = RTL_STATE_LANDED; - mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no RTL when landed"); - - /* if lower than return altitude, climb up first */ - } else if (_navigator->get_global_position()->alt < _navigator->get_home_position()->alt - + _param_return_alt.get()) { - _rtl_state = RTL_STATE_CLIMB; - - /* otherwise go straight to return */ - } else { - /* set altitude setpoint to current altitude */ - _rtl_state = RTL_STATE_RETURN; - _mission_item.altitude_is_relative = false; - _mission_item.altitude = _navigator->get_global_position()->alt; - } + /* decide where to enter the RTL procedure when we switch into it */ + if (_rtl_state == RTL_STATE_NONE) { + /* for safety reasons don't go into RTL if landed */ + if (_navigator->get_vstatus()->condition_landed) { + _rtl_state = RTL_STATE_LANDED; + mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: no RTL when landed"); + + /* if lower than return altitude, climb up first */ + } else if (_navigator->get_global_position()->alt < _navigator->get_home_position()->alt + + _param_return_alt.get()) { + _rtl_state = RTL_STATE_CLIMB; + + /* otherwise go straight to return */ + } else { + /* set altitude setpoint to current altitude */ + _rtl_state = RTL_STATE_RETURN; + _mission_item.altitude_is_relative = false; + _mission_item.altitude = _navigator->get_global_position()->alt; } + } - set_rtl_item(pos_sp_triplet); - updated = true; + set_rtl_item(pos_sp_triplet); +} - } else if (_rtl_state != RTL_STATE_LANDED && is_mission_item_reached()) { +bool +RTL::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) +{ + if (_rtl_state != RTL_STATE_LANDED && is_mission_item_reached()) { advance_rtl(); set_rtl_item(pos_sp_triplet); - updated = true; + return true; } - return updated; + return false; } void diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h index b4b729e89..9c8b3fdfc 100644 --- a/src/modules/navigator/rtl.h +++ b/src/modules/navigator/rtl.h @@ -57,29 +57,15 @@ class Navigator; class RTL : public MissionBlock { public: - /** - * Constructor - */ RTL(Navigator *navigator, const char *name); - /** - * Destructor - */ ~RTL(); - /** - * This function is called while the mode is inactive - */ - void on_inactive(); + virtual void on_inactive(); - /** - * This function is called while the mode is active - * - * @param position setpoint triplet that needs to be set - * @return true if updated - */ - bool on_active(position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_activation(position_setpoint_triplet_s *pos_sp_triplet); + virtual bool on_active(position_setpoint_triplet_s *pos_sp_triplet); private: /** -- cgit v1.2.3 From 12be974bd67676ef243d069593b179108976da22 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 29 Jun 2014 13:07:38 +0200 Subject: navigator: whitespace fix --- src/modules/navigator/mission.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 395669698..ab99a6b7e 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -255,7 +255,7 @@ Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet) "#audio: no mission available"); } _mission_type = MISSION_TYPE_NONE; - _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached); + _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached); set_loiter_item(pos_sp_triplet); pos_sp_triplet->previous.valid = false; -- cgit v1.2.3 From 628477ee2c75d16758688f53c0f8d9f29457f831 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 29 Jun 2014 14:01:58 +0200 Subject: Update estimator from Paul --- .../ekf_att_pos_estimator/estimator_23states.cpp | 610 ++++++++++++++++----- .../ekf_att_pos_estimator/estimator_23states.h | 20 +- .../ekf_att_pos_estimator/estimator_utilities.cpp | 19 + .../ekf_att_pos_estimator/estimator_utilities.h | 3 +- 4 files changed, 509 insertions(+), 143 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index e4b0c2b14..d77f4a6e3 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -25,6 +25,7 @@ AttPosEKF::AttPosEKF() useAirspeed = true; useCompass = true; useRangeFinder = true; + useOpticalFlow = true; numericalProtection = true; refSet = false; storeIndex = 0; @@ -227,10 +228,22 @@ void AttPosEKF::CovariancePrediction(float dt) // scale gyro bias noise when on ground to allow for faster bias estimation for (uint8_t i=10; i<=12; i++) processNoise[i] = dt * dAngBiasSigma; processNoise[13] = dVelBiasSigma; - for (uint8_t i=14; i<=15; i++) processNoise[i] = dt * windVelSigma; - for (uint8_t i=16; i<=18; i++) processNoise[i] = dt * magEarthSigma; - for (uint8_t i=19; i<=21; i++) processNoise[i] = dt * magBodySigma; - processNoise[22] = dt * sqrtf(sq(states[4]) + sq(states[5])) * gndHgtSigma; + if (!inhibitWindStates) { + for (uint8_t i=14; i<=15; i++) processNoise[i] = dt * windVelSigma; + } else { + for (uint8_t i=14; i<=15; i++) processNoise[i] = 0; + } + if (!inhibitMagStates) { + for (uint8_t i=16; i<=18; i++) processNoise[i] = dt * magEarthSigma; + for (uint8_t i=19; i<=21; i++) processNoise[i] = dt * magBodySigma; + } else { + for (uint8_t i=16; i<=21; i++) processNoise[i] = 0; + } + if (!inhibitGndHgtState) { + processNoise[22] = dt * sqrtf(sq(states[4]) + sq(states[5])) * gndHgtSigma; + } else { + processNoise[22] = 0; + } // square all sigmas for (unsigned i = 0; i < n_states; i++) processNoise[i] = sq(processNoise[i]); @@ -842,30 +855,6 @@ void AttPosEKF::CovariancePrediction(float dt) nextP[i][i] = nextP[i][i] + processNoise[i]; } - // If on ground or no magnetometer fitted, inhibit magnetometer bias updates by - // setting the coresponding covariance terms to zero. - if (onGround || !useCompass) - { - zeroRows(nextP,16,21); - zeroCols(nextP,16,21); - } - - // If on ground or not using airspeed sensing, inhibit wind velocity - // covariance growth. - if (onGround || !useAirspeed) - { - zeroRows(nextP,14,15); - zeroCols(nextP,14,15); - } - - // If on ground, inhibit terrain offset updates by - // setting the coresponding covariance terms to zero. - if (onGround) - { - zeroRows(nextP,22,22); - zeroCols(nextP,22,22); - } - // If the total position variance exceds 1E6 (1000m), then stop covariance // growth by setting the predicted to the previous values // This prevent an ill conditioned matrix from occurring for long periods @@ -882,48 +871,22 @@ void AttPosEKF::CovariancePrediction(float dt) } } - if (onGround || staticMode) { - // copy the portion of the variances we want to - // propagate - for (unsigned i = 0; i <= 13; i++) { - P[i][i] = nextP[i][i]; - } - - // force symmetry for observable states - // force zero for non-observable states - for (unsigned i = 1; i < n_states; i++) - { - for (uint8_t j = 0; j < i; j++) - { - if ((i > 13) || (j > 13)) { - P[i][j] = 0.0f; - } else { - P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]); - } - P[j][i] = P[i][j]; - } - } - - } else { - - // Copy covariance - for (unsigned i = 0; i < n_states; i++) { - P[i][i] = nextP[i][i]; - } + // Copy covariance + for (unsigned i = 0; i < n_states; i++) { + P[i][i] = nextP[i][i]; + } - // force symmetry for observable states - for (unsigned i = 1; i < n_states; i++) + // force symmetry for observable states + for (unsigned i = 1; i < n_states; i++) + { + for (uint8_t j = 0; j < i; j++) { - for (uint8_t j = 0; j < i; j++) - { - P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]); - P[j][i] = P[i][j]; - } + P[i][j] = 0.5f * (nextP[i][j] + nextP[j][i]); + P[j][i] = P[i][j]; } - } - ConstrainVariances(); + ConstrainVariances(); } void AttPosEKF::FuseVelposNED() @@ -944,7 +907,7 @@ void AttPosEKF::FuseVelposNED() bool fuseData[6] = {false,false,false,false,false,false}; uint8_t stateIndex; uint8_t obsIndex; - uint8_t indexLimit; + uint8_t indexLimit = 22; // declare variables used by state and covariance update calculations float velErr; @@ -981,11 +944,6 @@ void AttPosEKF::FuseVelposNED() R_OBS[4] = R_OBS[3]; R_OBS[5] = sq(posDSigma) + sq(posErr); - // Set innovation variances to zero default - for (uint8_t i = 0; i<=5; i++) - { - varInnovVelPos[i] = 0.0f; - } // calculate innovations and check GPS data validity using an innovation consistency check if (fuseVelData) { @@ -1071,15 +1029,6 @@ void AttPosEKF::FuseVelposNED() { fuseData[5] = true; } - // Limit range of states modified when on ground - if(!onGround) - { - indexLimit = 22; - } - else - { - indexLimit = 13; - } // Fuse measurements sequentially for (obsIndex=0; obsIndex<=5; obsIndex++) { @@ -1113,6 +1062,22 @@ void AttPosEKF::FuseVelposNED() if (obsIndex != 5) { Kfusion[13] = 0; } + // Don't update wind states if inhibited + if (inhibitWindStates) { + Kfusion[14] = 0; + Kfusion[15] = 0; + } + // Don't update magnetic field states if inhibited + if (inhibitMagStates) { + for (uint8_t i = 16; i<=21; i++) + { + Kfusion[i] = 0; + } + } + // Don't update terrain state if inhibited + if (inhibitGndHgtState) { + Kfusion[22] = 0; + } // Calculate state corrections and re-normalise the quaternions for (uint8_t i = 0; i<=indexLimit; i++) @@ -1179,7 +1144,6 @@ void AttPosEKF::FuseMagnetometer() for (uint8_t i = 0; i < n_states; i++) { H_MAG[i] = 0.0f; } - unsigned indexLimit; // Perform sequential fusion of Magnetometer measurements. // This assumes that the errors in the different components are @@ -1189,19 +1153,6 @@ void AttPosEKF::FuseMagnetometer() // associated with sequential fusion if (useCompass && fuseMagData && (obsIndex < 3)) { - // Limit range of states modified when on ground - if(!onGround) - { - indexLimit = n_states; - } - else - { - indexLimit = 13 + 1; - } - - // Sequential fusion of XYZ components to spread processing load across - // three prediction time steps. - // Calculate observation jacobians and Kalman gains if (obsIndex == 0) { @@ -1287,15 +1238,31 @@ void AttPosEKF::FuseMagnetometer() Kfusion[12] = SK_MX[0]*(P[12][19] + P[12][1]*SH_MAG[0] + P[12][3]*SH_MAG[2] + P[12][0]*SK_MX[3] - P[12][2]*SK_MX[2] - P[12][16]*SK_MX[1] + P[12][17]*SK_MX[5] - P[12][18]*SK_MX[4]); // Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate Kfusion[13] = 0.0f;//SK_MX[0]*(P[13][19] + P[13][1]*SH_MAG[0] + P[13][3]*SH_MAG[2] + P[13][0]*SK_MX[3] - P[13][2]*SK_MX[2] - P[13][16]*SK_MX[1] + P[13][17]*SK_MX[5] - P[13][18]*SK_MX[4]); - Kfusion[14] = SK_MX[0]*(P[14][19] + P[14][1]*SH_MAG[0] + P[14][3]*SH_MAG[2] + P[14][0]*SK_MX[3] - P[14][2]*SK_MX[2] - P[14][16]*SK_MX[1] + P[14][17]*SK_MX[5] - P[14][18]*SK_MX[4]); - Kfusion[15] = SK_MX[0]*(P[15][19] + P[15][1]*SH_MAG[0] + P[15][3]*SH_MAG[2] + P[15][0]*SK_MX[3] - P[15][2]*SK_MX[2] - P[15][16]*SK_MX[1] + P[15][17]*SK_MX[5] - P[15][18]*SK_MX[4]); - Kfusion[16] = SK_MX[0]*(P[16][19] + P[16][1]*SH_MAG[0] + P[16][3]*SH_MAG[2] + P[16][0]*SK_MX[3] - P[16][2]*SK_MX[2] - P[16][16]*SK_MX[1] + P[16][17]*SK_MX[5] - P[16][18]*SK_MX[4]); - Kfusion[17] = SK_MX[0]*(P[17][19] + P[17][1]*SH_MAG[0] + P[17][3]*SH_MAG[2] + P[17][0]*SK_MX[3] - P[17][2]*SK_MX[2] - P[17][16]*SK_MX[1] + P[17][17]*SK_MX[5] - P[17][18]*SK_MX[4]); - Kfusion[18] = SK_MX[0]*(P[18][19] + P[18][1]*SH_MAG[0] + P[18][3]*SH_MAG[2] + P[18][0]*SK_MX[3] - P[18][2]*SK_MX[2] - P[18][16]*SK_MX[1] + P[18][17]*SK_MX[5] - P[18][18]*SK_MX[4]); - Kfusion[19] = SK_MX[0]*(P[19][19] + P[19][1]*SH_MAG[0] + P[19][3]*SH_MAG[2] + P[19][0]*SK_MX[3] - P[19][2]*SK_MX[2] - P[19][16]*SK_MX[1] + P[19][17]*SK_MX[5] - P[19][18]*SK_MX[4]); - Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[3] - P[20][2]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[5] - P[20][18]*SK_MX[4]); - Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[3] - P[21][2]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[5] - P[21][18]*SK_MX[4]); - Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[3] - P[22][2]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[5] - P[22][18]*SK_MX[4]); + // Estimation of selected states is inhibited by setting their Kalman gains to zero + if (!inhibitWindStates) { + Kfusion[14] = SK_MX[0]*(P[14][19] + P[14][1]*SH_MAG[0] + P[14][3]*SH_MAG[2] + P[14][0]*SK_MX[3] - P[14][2]*SK_MX[2] - P[14][16]*SK_MX[1] + P[14][17]*SK_MX[5] - P[14][18]*SK_MX[4]); + Kfusion[15] = SK_MX[0]*(P[15][19] + P[15][1]*SH_MAG[0] + P[15][3]*SH_MAG[2] + P[15][0]*SK_MX[3] - P[15][2]*SK_MX[2] - P[15][16]*SK_MX[1] + P[15][17]*SK_MX[5] - P[15][18]*SK_MX[4]); + } else { + Kfusion[14] = 0; + Kfusion[15] = 0; + } + if (!inhibitMagStates) { + Kfusion[16] = SK_MX[0]*(P[16][19] + P[16][1]*SH_MAG[0] + P[16][3]*SH_MAG[2] + P[16][0]*SK_MX[3] - P[16][2]*SK_MX[2] - P[16][16]*SK_MX[1] + P[16][17]*SK_MX[5] - P[16][18]*SK_MX[4]); + Kfusion[17] = SK_MX[0]*(P[17][19] + P[17][1]*SH_MAG[0] + P[17][3]*SH_MAG[2] + P[17][0]*SK_MX[3] - P[17][2]*SK_MX[2] - P[17][16]*SK_MX[1] + P[17][17]*SK_MX[5] - P[17][18]*SK_MX[4]); + Kfusion[18] = SK_MX[0]*(P[18][19] + P[18][1]*SH_MAG[0] + P[18][3]*SH_MAG[2] + P[18][0]*SK_MX[3] - P[18][2]*SK_MX[2] - P[18][16]*SK_MX[1] + P[18][17]*SK_MX[5] - P[18][18]*SK_MX[4]); + Kfusion[19] = SK_MX[0]*(P[19][19] + P[19][1]*SH_MAG[0] + P[19][3]*SH_MAG[2] + P[19][0]*SK_MX[3] - P[19][2]*SK_MX[2] - P[19][16]*SK_MX[1] + P[19][17]*SK_MX[5] - P[19][18]*SK_MX[4]); + Kfusion[20] = SK_MX[0]*(P[20][19] + P[20][1]*SH_MAG[0] + P[20][3]*SH_MAG[2] + P[20][0]*SK_MX[3] - P[20][2]*SK_MX[2] - P[20][16]*SK_MX[1] + P[20][17]*SK_MX[5] - P[20][18]*SK_MX[4]); + Kfusion[21] = SK_MX[0]*(P[21][19] + P[21][1]*SH_MAG[0] + P[21][3]*SH_MAG[2] + P[21][0]*SK_MX[3] - P[21][2]*SK_MX[2] - P[21][16]*SK_MX[1] + P[21][17]*SK_MX[5] - P[21][18]*SK_MX[4]); + } else { + for (uint8_t i=16; i <= 21; i++) { + Kfusion[i] = 0; + } + } + if (!inhibitGndHgtState) { + Kfusion[22] = SK_MX[0]*(P[22][19] + P[22][1]*SH_MAG[0] + P[22][3]*SH_MAG[2] + P[22][0]*SK_MX[3] - P[22][2]*SK_MX[2] - P[22][16]*SK_MX[1] + P[22][17]*SK_MX[5] - P[22][18]*SK_MX[4]); + } else { + Kfusion[22] = 0; + } varInnovMag[0] = 1.0f/SK_MX[0]; innovMag[0] = MagPred[0] - magData.x; } @@ -1342,15 +1309,34 @@ void AttPosEKF::FuseMagnetometer() Kfusion[12] = SK_MY[0]*(P[12][20] + P[12][0]*SH_MAG[2] + P[12][1]*SH_MAG[1] + P[12][2]*SH_MAG[0] - P[12][3]*SK_MY[2] - P[12][17]*SK_MY[1] - P[12][16]*SK_MY[3] + P[12][18]*SK_MY[4]); // Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate Kfusion[13] = 0.0f;//SK_MY[0]*(P[13][20] + P[13][0]*SH_MAG[2] + P[13][1]*SH_MAG[1] + P[13][2]*SH_MAG[0] - P[13][3]*SK_MY[2] - P[13][17]*SK_MY[1] - P[13][16]*SK_MY[3] + P[13][18]*SK_MY[4]); - Kfusion[14] = SK_MY[0]*(P[14][20] + P[14][0]*SH_MAG[2] + P[14][1]*SH_MAG[1] + P[14][2]*SH_MAG[0] - P[14][3]*SK_MY[2] - P[14][17]*SK_MY[1] - P[14][16]*SK_MY[3] + P[14][18]*SK_MY[4]); - Kfusion[15] = SK_MY[0]*(P[15][20] + P[15][0]*SH_MAG[2] + P[15][1]*SH_MAG[1] + P[15][2]*SH_MAG[0] - P[15][3]*SK_MY[2] - P[15][17]*SK_MY[1] - P[15][16]*SK_MY[3] + P[15][18]*SK_MY[4]); - Kfusion[16] = SK_MY[0]*(P[16][20] + P[16][0]*SH_MAG[2] + P[16][1]*SH_MAG[1] + P[16][2]*SH_MAG[0] - P[16][3]*SK_MY[2] - P[16][17]*SK_MY[1] - P[16][16]*SK_MY[3] + P[16][18]*SK_MY[4]); - Kfusion[17] = SK_MY[0]*(P[17][20] + P[17][0]*SH_MAG[2] + P[17][1]*SH_MAG[1] + P[17][2]*SH_MAG[0] - P[17][3]*SK_MY[2] - P[17][17]*SK_MY[1] - P[17][16]*SK_MY[3] + P[17][18]*SK_MY[4]); - Kfusion[18] = SK_MY[0]*(P[18][20] + P[18][0]*SH_MAG[2] + P[18][1]*SH_MAG[1] + P[18][2]*SH_MAG[0] - P[18][3]*SK_MY[2] - P[18][17]*SK_MY[1] - P[18][16]*SK_MY[3] + P[18][18]*SK_MY[4]); - Kfusion[19] = SK_MY[0]*(P[19][20] + P[19][0]*SH_MAG[2] + P[19][1]*SH_MAG[1] + P[19][2]*SH_MAG[0] - P[19][3]*SK_MY[2] - P[19][17]*SK_MY[1] - P[19][16]*SK_MY[3] + P[19][18]*SK_MY[4]); - Kfusion[20] = SK_MY[0]*(P[20][20] + P[20][0]*SH_MAG[2] + P[20][1]*SH_MAG[1] + P[20][2]*SH_MAG[0] - P[20][3]*SK_MY[2] - P[20][17]*SK_MY[1] - P[20][16]*SK_MY[3] + P[20][18]*SK_MY[4]); - Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][0]*SH_MAG[2] + P[21][1]*SH_MAG[1] + P[21][2]*SH_MAG[0] - P[21][3]*SK_MY[2] - P[21][17]*SK_MY[1] - P[21][16]*SK_MY[3] + P[21][18]*SK_MY[4]); - Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]); + // Estimation of selected states is inhibited by setting their Kalman gains to zero + if (!inhibitWindStates) { + Kfusion[14] = SK_MY[0]*(P[14][20] + P[14][0]*SH_MAG[2] + P[14][1]*SH_MAG[1] + P[14][2]*SH_MAG[0] - P[14][3]*SK_MY[2] - P[14][17]*SK_MY[1] - P[14][16]*SK_MY[3] + P[14][18]*SK_MY[4]); + Kfusion[15] = SK_MY[0]*(P[15][20] + P[15][0]*SH_MAG[2] + P[15][1]*SH_MAG[1] + P[15][2]*SH_MAG[0] - P[15][3]*SK_MY[2] - P[15][17]*SK_MY[1] - P[15][16]*SK_MY[3] + P[15][18]*SK_MY[4]); + } else { + Kfusion[14] = 0; + Kfusion[15] = 0; + } + if (!inhibitMagStates) { + Kfusion[16] = SK_MY[0]*(P[16][20] + P[16][0]*SH_MAG[2] + P[16][1]*SH_MAG[1] + P[16][2]*SH_MAG[0] - P[16][3]*SK_MY[2] - P[16][17]*SK_MY[1] - P[16][16]*SK_MY[3] + P[16][18]*SK_MY[4]); + Kfusion[17] = SK_MY[0]*(P[17][20] + P[17][0]*SH_MAG[2] + P[17][1]*SH_MAG[1] + P[17][2]*SH_MAG[0] - P[17][3]*SK_MY[2] - P[17][17]*SK_MY[1] - P[17][16]*SK_MY[3] + P[17][18]*SK_MY[4]); + Kfusion[18] = SK_MY[0]*(P[18][20] + P[18][0]*SH_MAG[2] + P[18][1]*SH_MAG[1] + P[18][2]*SH_MAG[0] - P[18][3]*SK_MY[2] - P[18][17]*SK_MY[1] - P[18][16]*SK_MY[3] + P[18][18]*SK_MY[4]); + Kfusion[19] = SK_MY[0]*(P[19][20] + P[19][0]*SH_MAG[2] + P[19][1]*SH_MAG[1] + P[19][2]*SH_MAG[0] - P[19][3]*SK_MY[2] - P[19][17]*SK_MY[1] - P[19][16]*SK_MY[3] + P[19][18]*SK_MY[4]); + Kfusion[20] = SK_MY[0]*(P[20][20] + P[20][0]*SH_MAG[2] + P[20][1]*SH_MAG[1] + P[20][2]*SH_MAG[0] - P[20][3]*SK_MY[2] - P[20][17]*SK_MY[1] - P[20][16]*SK_MY[3] + P[20][18]*SK_MY[4]); + Kfusion[21] = SK_MY[0]*(P[21][20] + P[21][0]*SH_MAG[2] + P[21][1]*SH_MAG[1] + P[21][2]*SH_MAG[0] - P[21][3]*SK_MY[2] - P[21][17]*SK_MY[1] - P[21][16]*SK_MY[3] + P[21][18]*SK_MY[4]); + } else { + Kfusion[16] = 0; + Kfusion[17] = 0; + Kfusion[18] = 0; + Kfusion[19] = 0; + Kfusion[20] = 0; + Kfusion[21] = 0; + } + if (!inhibitGndHgtState) { + Kfusion[22] = SK_MY[0]*(P[22][20] + P[22][0]*SH_MAG[2] + P[22][1]*SH_MAG[1] + P[22][2]*SH_MAG[0] - P[22][3]*SK_MY[2] - P[22][17]*SK_MY[1] - P[22][16]*SK_MY[3] + P[22][18]*SK_MY[4]); + } else { + Kfusion[22] = 0; + } varInnovMag[1] = 1.0f/SK_MY[0]; innovMag[1] = MagPred[1] - magData.y; } @@ -1398,15 +1384,34 @@ void AttPosEKF::FuseMagnetometer() Kfusion[12] = SK_MZ[0]*(P[12][21] + P[12][0]*SH_MAG[1] + P[12][3]*SH_MAG[0] - P[12][1]*SK_MZ[2] + P[12][2]*SK_MZ[3] + P[12][18]*SK_MZ[1] + P[12][16]*SK_MZ[5] - P[12][17]*SK_MZ[4]); // Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate Kfusion[13] = 0.0f;//SK_MZ[0]*(P[13][21] + P[13][0]*SH_MAG[1] + P[13][3]*SH_MAG[0] - P[13][1]*SK_MZ[2] + P[13][2]*SK_MZ[3] + P[13][18]*SK_MZ[1] + P[13][16]*SK_MZ[5] - P[13][17]*SK_MZ[4]); - Kfusion[14] = SK_MZ[0]*(P[14][21] + P[14][0]*SH_MAG[1] + P[14][3]*SH_MAG[0] - P[14][1]*SK_MZ[2] + P[14][2]*SK_MZ[3] + P[14][18]*SK_MZ[1] + P[14][16]*SK_MZ[5] - P[14][17]*SK_MZ[4]); - Kfusion[15] = SK_MZ[0]*(P[15][21] + P[15][0]*SH_MAG[1] + P[15][3]*SH_MAG[0] - P[15][1]*SK_MZ[2] + P[15][2]*SK_MZ[3] + P[15][18]*SK_MZ[1] + P[15][16]*SK_MZ[5] - P[15][17]*SK_MZ[4]); - Kfusion[16] = SK_MZ[0]*(P[16][21] + P[16][0]*SH_MAG[1] + P[16][3]*SH_MAG[0] - P[16][1]*SK_MZ[2] + P[16][2]*SK_MZ[3] + P[16][18]*SK_MZ[1] + P[16][16]*SK_MZ[5] - P[16][17]*SK_MZ[4]); - Kfusion[17] = SK_MZ[0]*(P[17][21] + P[17][0]*SH_MAG[1] + P[17][3]*SH_MAG[0] - P[17][1]*SK_MZ[2] + P[17][2]*SK_MZ[3] + P[17][18]*SK_MZ[1] + P[17][16]*SK_MZ[5] - P[17][17]*SK_MZ[4]); - Kfusion[18] = SK_MZ[0]*(P[18][21] + P[18][0]*SH_MAG[1] + P[18][3]*SH_MAG[0] - P[18][1]*SK_MZ[2] + P[18][2]*SK_MZ[3] + P[18][18]*SK_MZ[1] + P[18][16]*SK_MZ[5] - P[18][17]*SK_MZ[4]); - Kfusion[19] = SK_MZ[0]*(P[19][21] + P[19][0]*SH_MAG[1] + P[19][3]*SH_MAG[0] - P[19][1]*SK_MZ[2] + P[19][2]*SK_MZ[3] + P[19][18]*SK_MZ[1] + P[19][16]*SK_MZ[5] - P[19][17]*SK_MZ[4]); - Kfusion[20] = SK_MZ[0]*(P[20][21] + P[20][0]*SH_MAG[1] + P[20][3]*SH_MAG[0] - P[20][1]*SK_MZ[2] + P[20][2]*SK_MZ[3] + P[20][18]*SK_MZ[1] + P[20][16]*SK_MZ[5] - P[20][17]*SK_MZ[4]); - Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][0]*SH_MAG[1] + P[21][3]*SH_MAG[0] - P[21][1]*SK_MZ[2] + P[21][2]*SK_MZ[3] + P[21][18]*SK_MZ[1] + P[21][16]*SK_MZ[5] - P[21][17]*SK_MZ[4]); - Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] + P[22][3]*SH_MAG[0] - P[22][1]*SK_MZ[2] + P[22][2]*SK_MZ[3] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[5] - P[22][17]*SK_MZ[4]); + // Estimation of selected states is inhibited by setting their Kalman gains to zero + if (!inhibitWindStates) { + Kfusion[14] = SK_MZ[0]*(P[14][21] + P[14][0]*SH_MAG[1] + P[14][3]*SH_MAG[0] - P[14][1]*SK_MZ[2] + P[14][2]*SK_MZ[3] + P[14][18]*SK_MZ[1] + P[14][16]*SK_MZ[5] - P[14][17]*SK_MZ[4]); + Kfusion[15] = SK_MZ[0]*(P[15][21] + P[15][0]*SH_MAG[1] + P[15][3]*SH_MAG[0] - P[15][1]*SK_MZ[2] + P[15][2]*SK_MZ[3] + P[15][18]*SK_MZ[1] + P[15][16]*SK_MZ[5] - P[15][17]*SK_MZ[4]); + } else { + Kfusion[14] = 0; + Kfusion[15] = 0; + } + if (!inhibitMagStates) { + Kfusion[16] = SK_MZ[0]*(P[16][21] + P[16][0]*SH_MAG[1] + P[16][3]*SH_MAG[0] - P[16][1]*SK_MZ[2] + P[16][2]*SK_MZ[3] + P[16][18]*SK_MZ[1] + P[16][16]*SK_MZ[5] - P[16][17]*SK_MZ[4]); + Kfusion[17] = SK_MZ[0]*(P[17][21] + P[17][0]*SH_MAG[1] + P[17][3]*SH_MAG[0] - P[17][1]*SK_MZ[2] + P[17][2]*SK_MZ[3] + P[17][18]*SK_MZ[1] + P[17][16]*SK_MZ[5] - P[17][17]*SK_MZ[4]); + Kfusion[18] = SK_MZ[0]*(P[18][21] + P[18][0]*SH_MAG[1] + P[18][3]*SH_MAG[0] - P[18][1]*SK_MZ[2] + P[18][2]*SK_MZ[3] + P[18][18]*SK_MZ[1] + P[18][16]*SK_MZ[5] - P[18][17]*SK_MZ[4]); + Kfusion[19] = SK_MZ[0]*(P[19][21] + P[19][0]*SH_MAG[1] + P[19][3]*SH_MAG[0] - P[19][1]*SK_MZ[2] + P[19][2]*SK_MZ[3] + P[19][18]*SK_MZ[1] + P[19][16]*SK_MZ[5] - P[19][17]*SK_MZ[4]); + Kfusion[20] = SK_MZ[0]*(P[20][21] + P[20][0]*SH_MAG[1] + P[20][3]*SH_MAG[0] - P[20][1]*SK_MZ[2] + P[20][2]*SK_MZ[3] + P[20][18]*SK_MZ[1] + P[20][16]*SK_MZ[5] - P[20][17]*SK_MZ[4]); + Kfusion[21] = SK_MZ[0]*(P[21][21] + P[21][0]*SH_MAG[1] + P[21][3]*SH_MAG[0] - P[21][1]*SK_MZ[2] + P[21][2]*SK_MZ[3] + P[21][18]*SK_MZ[1] + P[21][16]*SK_MZ[5] - P[21][17]*SK_MZ[4]); + } else { + Kfusion[16] = 0; + Kfusion[17] = 0; + Kfusion[18] = 0; + Kfusion[19] = 0; + Kfusion[20] = 0; + Kfusion[21] = 0; + } + if (!inhibitGndHgtState) { + Kfusion[22] = SK_MZ[0]*(P[22][21] + P[22][0]*SH_MAG[1] + P[22][3]*SH_MAG[0] - P[22][1]*SK_MZ[2] + P[22][2]*SK_MZ[3] + P[22][18]*SK_MZ[1] + P[22][16]*SK_MZ[5] - P[22][17]*SK_MZ[4]); + } else { + Kfusion[22] = 0; + } varInnovMag[2] = 1.0f/SK_MZ[0]; innovMag[2] = MagPred[2] - magData.z; @@ -1416,7 +1421,7 @@ void AttPosEKF::FuseMagnetometer() if ((innovMag[obsIndex]*innovMag[obsIndex]/varInnovMag[obsIndex]) < 25.0f) { // correct the state vector - for (uint8_t j= 0; j < indexLimit; j++) + for (uint8_t j= 0; j < n_states; j++) { states[j] = states[j] - Kfusion[j] * innovMag[obsIndex]; } @@ -1433,7 +1438,7 @@ void AttPosEKF::FuseMagnetometer() // correct the covariance P = (I - K*H)*P // take advantage of the empty columns in KH to reduce the // number of operations - for (uint8_t i = 0; i < indexLimit; i++) + for (uint8_t i = 0; i < n_states; i++) { for (uint8_t j = 0; j <= 3; j++) { @@ -1455,9 +1460,9 @@ void AttPosEKF::FuseMagnetometer() } } } - for (uint8_t i = 0; i < indexLimit; i++) + for (uint8_t i = 0; i < n_states; i++) { - for (uint8_t j = 0; j < indexLimit; j++) + for (uint8_t j = 0; j < n_states; j++) { KHP[i][j] = 0.0f; for (uint8_t k = 0; k <= 3; k++) @@ -1474,9 +1479,9 @@ void AttPosEKF::FuseMagnetometer() } } } - for (uint8_t i = 0; i < indexLimit; i++) + for (uint8_t i = 0; i < n_states; i++) { - for (uint8_t j = 0; j < indexLimit; j++) + for (uint8_t j = 0; j < n_states; j++) { P[i][j] = P[i][j] - KHP[i][j]; } @@ -1552,15 +1557,31 @@ void AttPosEKF::FuseAirspeed() Kfusion[12] = SK_TAS*(P[12][4]*SH_TAS[2] - P[12][14]*SH_TAS[2] + P[12][5]*SH_TAS[1] - P[12][15]*SH_TAS[1] + P[12][6]*vd*SH_TAS[0]); // Only height measurements are allowed to modify the Z delta velocity bias state. This improves the stability of the estimate Kfusion[13] = 0.0f;//SK_TAS*(P[13][4]*SH_TAS[2] - P[13][14]*SH_TAS[2] + P[13][5]*SH_TAS[1] - P[13][15]*SH_TAS[1] + P[13][6]*vd*SH_TAS[0]); - Kfusion[14] = SK_TAS*(P[14][4]*SH_TAS[2] - P[14][14]*SH_TAS[2] + P[14][5]*SH_TAS[1] - P[14][15]*SH_TAS[1] + P[14][6]*vd*SH_TAS[0]); - Kfusion[15] = SK_TAS*(P[15][4]*SH_TAS[2] - P[15][14]*SH_TAS[2] + P[15][5]*SH_TAS[1] - P[15][15]*SH_TAS[1] + P[15][6]*vd*SH_TAS[0]); - Kfusion[16] = SK_TAS*(P[16][4]*SH_TAS[2] - P[16][14]*SH_TAS[2] + P[16][5]*SH_TAS[1] - P[16][15]*SH_TAS[1] + P[16][6]*vd*SH_TAS[0]); - Kfusion[17] = SK_TAS*(P[17][4]*SH_TAS[2] - P[17][14]*SH_TAS[2] + P[17][5]*SH_TAS[1] - P[17][15]*SH_TAS[1] + P[17][6]*vd*SH_TAS[0]); - Kfusion[18] = SK_TAS*(P[18][4]*SH_TAS[2] - P[18][14]*SH_TAS[2] + P[18][5]*SH_TAS[1] - P[18][15]*SH_TAS[1] + P[18][6]*vd*SH_TAS[0]); - Kfusion[19] = SK_TAS*(P[19][4]*SH_TAS[2] - P[19][14]*SH_TAS[2] + P[19][5]*SH_TAS[1] - P[19][15]*SH_TAS[1] + P[19][6]*vd*SH_TAS[0]); - Kfusion[20] = SK_TAS*(P[20][4]*SH_TAS[2] - P[20][14]*SH_TAS[2] + P[20][5]*SH_TAS[1] - P[20][15]*SH_TAS[1] + P[20][6]*vd*SH_TAS[0]); - Kfusion[21] = SK_TAS*(P[21][4]*SH_TAS[2] - P[21][14]*SH_TAS[2] + P[21][5]*SH_TAS[1] - P[21][15]*SH_TAS[1] + P[21][6]*vd*SH_TAS[0]); - Kfusion[22] = SK_TAS*(P[22][4]*SH_TAS[2] - P[22][14]*SH_TAS[2] + P[22][5]*SH_TAS[1] - P[22][15]*SH_TAS[1] + P[22][6]*vd*SH_TAS[0]); + // Estimation of selected states is inhibited by setting their Kalman gains to zero + if (!inhibitWindStates) { + Kfusion[14] = SK_TAS*(P[14][4]*SH_TAS[2] - P[14][14]*SH_TAS[2] + P[14][5]*SH_TAS[1] - P[14][15]*SH_TAS[1] + P[14][6]*vd*SH_TAS[0]); + Kfusion[15] = SK_TAS*(P[15][4]*SH_TAS[2] - P[15][14]*SH_TAS[2] + P[15][5]*SH_TAS[1] - P[15][15]*SH_TAS[1] + P[15][6]*vd*SH_TAS[0]); + } else { + Kfusion[14] = 0; + Kfusion[15] = 0; + } + if (!inhibitMagStates) { + Kfusion[16] = SK_TAS*(P[16][4]*SH_TAS[2] - P[16][14]*SH_TAS[2] + P[16][5]*SH_TAS[1] - P[16][15]*SH_TAS[1] + P[16][6]*vd*SH_TAS[0]); + Kfusion[17] = SK_TAS*(P[17][4]*SH_TAS[2] - P[17][14]*SH_TAS[2] + P[17][5]*SH_TAS[1] - P[17][15]*SH_TAS[1] + P[17][6]*vd*SH_TAS[0]); + Kfusion[18] = SK_TAS*(P[18][4]*SH_TAS[2] - P[18][14]*SH_TAS[2] + P[18][5]*SH_TAS[1] - P[18][15]*SH_TAS[1] + P[18][6]*vd*SH_TAS[0]); + Kfusion[19] = SK_TAS*(P[19][4]*SH_TAS[2] - P[19][14]*SH_TAS[2] + P[19][5]*SH_TAS[1] - P[19][15]*SH_TAS[1] + P[19][6]*vd*SH_TAS[0]); + Kfusion[20] = SK_TAS*(P[20][4]*SH_TAS[2] - P[20][14]*SH_TAS[2] + P[20][5]*SH_TAS[1] - P[20][15]*SH_TAS[1] + P[20][6]*vd*SH_TAS[0]); + Kfusion[21] = SK_TAS*(P[21][4]*SH_TAS[2] - P[21][14]*SH_TAS[2] + P[21][5]*SH_TAS[1] - P[21][15]*SH_TAS[1] + P[21][6]*vd*SH_TAS[0]); + } else { + for (uint8_t i=16; i <= 21; i++) { + Kfusion[i] = 0; + } + } + if (!inhibitGndHgtState) { + Kfusion[22] = SK_TAS*(P[22][4]*SH_TAS[2] - P[22][14]*SH_TAS[2] + P[22][5]*SH_TAS[1] - P[22][15]*SH_TAS[1] + P[22][6]*vd*SH_TAS[0]); + } else { + Kfusion[22] = 0; + } varInnovVtas = 1.0f/SK_TAS; // Calculate the measurement innovation @@ -1662,9 +1683,9 @@ void AttPosEKF::FuseRangeFinder() float ptd = statesAtRngTime[22]; // Need to check that our range finder tilt angle is less than 30 degrees and we are using range finder data - SH_RNG[4] = sin(rngFinderPitch); + SH_RNG[4] = sinf(rngFinderPitch); cosRngTilt = - Tbn.z.x * SH_RNG[4] + Tbn.z.z * cosf(rngFinderPitch); - if (useRangeFinder && cosRngTilt > 0.87f) + if (useRangeFinder && fuseRngData && cosRngTilt > 0.87f) { // Calculate observation jacobian and Kalman gain ignoring all states other than the terrain offset // This prevents the range finder measurement modifying any of the other filter states and significantly reduces computations @@ -1685,10 +1706,12 @@ void AttPosEKF::FuseRangeFinder() SK_RNG[5] = SH_RNG[2]; Kfusion[22] = SK_RNG[0]*(P[22][9]*SH_RNG[3] - P[22][22]*SH_RNG[3] + P[22][0]*SH_RNG[1]*SK_RNG[2]*SK_RNG[5] - P[22][1]*SH_RNG[1]*SK_RNG[1]*SK_RNG[5] - P[22][2]*SH_RNG[1]*SK_RNG[4]*SK_RNG[5] + P[22][3]*SH_RNG[1]*SK_RNG[3]*SK_RNG[5]); + // Calculate the innovation variance for data logging + varInnovRng = 1.0f/SK_RNG[0]; + // Calculate the measurement innovation rngPred = (ptd - pd)/cosRngTilt; innovRng = rngPred - rngMea; - //printf("mea=%5.1f, pred=%5.1f, pd=%5.1f, ptd=%5.2f\n", rngMea, rngPred, pd, ptd); // Check the innovation for consistency and don't fuse if > 5Sigma if ((innovRng*innovRng*SK_RNG[0]) < 25) @@ -1704,6 +1727,293 @@ void AttPosEKF::FuseRangeFinder() } +void AttPosEKF::FuseOptFlow() +{ + static uint8_t obsIndex; + static float SH_LOS[13]; + static float SKK_LOS[15]; + static float SK_LOS[2]; + static float q0 = 0.0f; + static float q1 = 0.0f; + static float q2 = 0.0f; + static float q3 = 1.0f; + static float vn = 0.0f; + static float ve = 0.0f; + static float vd = 0.0f; + static float pd = 0.0f; + static float ptd = 0.0f; + static Vector3f delAng; + static float R_LOS = 0.01f; + static float losPred[2]; + + // Transformation matrix from nav to body axes + Mat3f Tnb; + // Transformation matrix from body to sensor axes + // assume camera is aligned with Z body axis plus a misalignment + // defined by 3 small angles about X, Y and Z body axis + Mat3f Tbs; + Tbs.x.y = a3; + Tbs.y.x = -a3; + Tbs.x.z = -a2; + Tbs.z.x = a2; + Tbs.y.z = a1; + Tbs.z.y = -a1; + // Transformation matrix from navigation to sensor axes + Mat3f Tns; + float H_LOS[n_states]; + for (uint8_t i = 0; i < n_states; i++) { + H_LOS[i] = 0.0f; + } + Vector3f velNED; + Vector3f relVelSensor; + +// Perform sequential fusion of optical flow measurements only when in the air and tilt is less than 30 deg. + if (useOpticalFlow && (fuseOptFlowData || obsIndex == 1) && !onGround && Tbs.z.z > 0.866f && rngMea > 5.0f && rngMea < 39.0f) + { + // Sequential fusion of XY components to spread processing load across + // two prediction time steps. + + // Calculate observation jacobians and Kalman gains + if (fuseOptFlowData) + { + // Copy required states to local variable names + q0 = statesAtOptFlowTime[0]; + q1 = statesAtOptFlowTime[1]; + q2 = statesAtOptFlowTime[2]; + q3 = statesAtOptFlowTime[3]; + vn = statesAtOptFlowTime[4]; + ve = statesAtOptFlowTime[5]; + vd = statesAtOptFlowTime[6]; + pd = statesAtOptFlowTime[9]; + ptd = statesAtOptFlowTime[22]; + velNED.x = vn; + velNED.y = ve; + velNED.z = vd; + + // calculate rotation from NED to body axes + float q00 = sq(q0); + float q11 = sq(q1); + float q22 = sq(q2); + float q33 = sq(q3); + float q01 = q0 * q1; + float q02 = q0 * q2; + float q03 = q0 * q3; + float q12 = q1 * q2; + float q13 = q1 * q3; + float q23 = q2 * q3; + Tnb.x.x = q00 + q11 - q22 - q33; + Tnb.y.y = q00 - q11 + q22 - q33; + Tnb.z.z = q00 - q11 - q22 + q33; + Tnb.y.x = 2*(q12 - q03); + Tnb.z.x = 2*(q13 + q02); + Tnb.x.y = 2*(q12 + q03); + Tnb.z.y = 2*(q23 - q01); + Tnb.x.z = 2*(q13 - q02); + Tnb.y.z = 2*(q23 + q01); + + // calculate transformation from NED to sensor axes + Tns = Tbs*Tnb; + + // calculate range from ground plain to centre of sensor fov assuming flat earth + float range = ConstrainFloat(((ptd - pd)/Tns.z.z),0.5f,100.0f); + + // calculate relative velocity in sensor frame + relVelSensor = Tns*velNED; + + // calculate delta angles in sensor axes + Vector3f delAngRel = Tbs*delAng; + + // divide velocity by range and include angular rate effects to get predicted angular LOS rates relative to X and Y axes + losPred[0] = relVelSensor.y/range; + losPred[1] = -relVelSensor.x/range; + + //printf("relVelSensor.x=%5.1f, relVelSensor.y=%5.1f\n", relVelSensor.x, relVelSensor.y); + //printf("Xpred=%5.2f, Xmea=%5.2f, Ypred=%5.2f, Ymea=%5.2f, delAng.x=%4.4f, delAng.y=%4.4f\n", losPred[0], losData[0], losPred[1], losData[1], delAng.x, delAng.y); + //printf("omegaX=%5.2f, omegaY=%5.2f, velY=%5.1f velX=%5.1f\n, range=%5.1f\n", delAngRel.x/dt, delAngRel.y/dt, relVelSensor.y, relVelSensor.x, range); + + // Calculate observation jacobians + SH_LOS[0] = a1*(2*q0*q1 + 2*q2*q3) + a2*(2*q0*q2 - 2*q1*q3) - sq(q0) + sq(q1) + sq(q2) - sq(q3); + SH_LOS[1] = vd*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3)) - ve*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3)) + vn*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3)); + SH_LOS[2] = ve*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3)) - vd*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3)) + vn*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3)); + SH_LOS[3] = 1/(pd - ptd); + SH_LOS[4] = 2*q1 - 2*a2*q3 + 2*a3*q2; + SH_LOS[5] = 2*a2*q2 - 2*q0 + 2*a3*q3; + SH_LOS[6] = 2*q2 + 2*a2*q0 - 2*a3*q1; + SH_LOS[7] = 1/sq(pd - ptd); + SH_LOS[8] = 2*q2 + 2*a1*q3 - 2*a3*q1; + SH_LOS[9] = 2*q3 - 2*a1*q2 + 2*a3*q0; + SH_LOS[10] = 2*a1*q1 - 2*q0 + 2*a3*q3; + SH_LOS[11] = 2*q3 + 2*a2*q1 + 2*a3*q0; + SH_LOS[12] = 2*q1 + 2*a1*q0 + 2*a3*q2; + + for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0; + H_LOS[0] = - SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]); + H_LOS[1] = - SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]); + H_LOS[2] = SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]) - SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3); + H_LOS[3] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]); + H_LOS[4] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3)); + H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3)); + H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3)); + H_LOS[9] = SH_LOS[0]*SH_LOS[2]*SH_LOS[7]; + H_LOS[22] = -SH_LOS[0]*SH_LOS[2]*SH_LOS[7]; + + // Calculate Kalman gain + SKK_LOS[0] = a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3); + SKK_LOS[1] = a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3); + SKK_LOS[2] = a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3); + SKK_LOS[3] = a1*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q1 + 2*q2*q3 + a3*(2*q0*q2 - 2*q1*q3); + SKK_LOS[4] = a1*(2*q0*q1 - 2*q2*q3) + a3*(2*q0*q3 + 2*q1*q2) - sq(q0) + sq(q1) - sq(q2) + sq(q3); + SKK_LOS[5] = a3*(sq(q0) + sq(q1) - sq(q2) - sq(q3)) + 2*q0*q3 - 2*q1*q2 - a1*(2*q0*q2 + 2*q1*q3); + SKK_LOS[6] = SH_LOS[2]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[8] - ve*SH_LOS[9] + vn*SH_LOS[10]); + SKK_LOS[7] = SH_LOS[2]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[10] + ve*SH_LOS[12] - vn*SH_LOS[8]); + SKK_LOS[8] = SH_LOS[2]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[10] - vd*SH_LOS[12] + vn*SH_LOS[9]); + SKK_LOS[9] = SH_LOS[2]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[9] + ve*SH_LOS[8] + vn*SH_LOS[12]); + SKK_LOS[10] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]); + SKK_LOS[11] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]); + SKK_LOS[12] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]); + SKK_LOS[13] = SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]); + SKK_LOS[14] = SH_LOS[0]; + + SK_LOS[0] = 1/(R_LOS + SKK_LOS[8]*(P[0][0]*SKK_LOS[8] + P[1][0]*SKK_LOS[7] + P[2][0]*SKK_LOS[9] - P[3][0]*SKK_LOS[6] - P[9][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][0]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][0]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[7]*(P[0][1]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] + P[2][1]*SKK_LOS[9] - P[3][1]*SKK_LOS[6] - P[9][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][1]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][1]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SKK_LOS[9]*(P[0][2]*SKK_LOS[8] + P[1][2]*SKK_LOS[7] + P[2][2]*SKK_LOS[9] - P[3][2]*SKK_LOS[6] - P[9][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][2]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][2]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SKK_LOS[6]*(P[0][3]*SKK_LOS[8] + P[1][3]*SKK_LOS[7] + P[2][3]*SKK_LOS[9] - P[3][3]*SKK_LOS[6] - P[9][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][3]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][3]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[8] + P[1][9]*SKK_LOS[7] + P[2][9]*SKK_LOS[9] - P[3][9]*SKK_LOS[6] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][9]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][9]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[2]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[8] + P[1][22]*SKK_LOS[7] + P[2][22]*SKK_LOS[9] - P[3][22]*SKK_LOS[6] - P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][22]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][22]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14]*(P[0][4]*SKK_LOS[8] + P[1][4]*SKK_LOS[7] + P[2][4]*SKK_LOS[9] - P[3][4]*SKK_LOS[6] - P[9][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][4]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14]*(P[0][5]*SKK_LOS[8] + P[1][5]*SKK_LOS[7] + P[2][5]*SKK_LOS[9] - P[3][5]*SKK_LOS[6] - P[9][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]*(P[0][6]*SKK_LOS[8] + P[1][6]*SKK_LOS[7] + P[2][6]*SKK_LOS[9] - P[3][6]*SKK_LOS[6] - P[9][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14])); + Kfusion[0] = -SK_LOS[0]*(P[0][0]*SKK_LOS[8] + P[0][1]*SKK_LOS[7] - P[0][3]*SKK_LOS[6] + P[0][2]*SKK_LOS[9] - P[0][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[0][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[0][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[1] = -SK_LOS[0]*(P[1][0]*SKK_LOS[8] + P[1][1]*SKK_LOS[7] - P[1][3]*SKK_LOS[6] + P[1][2]*SKK_LOS[9] - P[1][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[1][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[1][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[2] = -SK_LOS[0]*(P[2][0]*SKK_LOS[8] + P[2][1]*SKK_LOS[7] - P[2][3]*SKK_LOS[6] + P[2][2]*SKK_LOS[9] - P[2][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[2][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[2][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[3] = -SK_LOS[0]*(P[3][0]*SKK_LOS[8] + P[3][1]*SKK_LOS[7] - P[3][3]*SKK_LOS[6] + P[3][2]*SKK_LOS[9] - P[3][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[3][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[3][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[4] = -SK_LOS[0]*(P[4][0]*SKK_LOS[8] + P[4][1]*SKK_LOS[7] - P[4][3]*SKK_LOS[6] + P[4][2]*SKK_LOS[9] - P[4][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[4][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[5] = -SK_LOS[0]*(P[5][0]*SKK_LOS[8] + P[5][1]*SKK_LOS[7] - P[5][3]*SKK_LOS[6] + P[5][2]*SKK_LOS[9] - P[5][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[5][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[6] = -SK_LOS[0]*(P[6][0]*SKK_LOS[8] + P[6][1]*SKK_LOS[7] - P[6][3]*SKK_LOS[6] + P[6][2]*SKK_LOS[9] - P[6][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[6][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[7] = -SK_LOS[0]*(P[7][0]*SKK_LOS[8] + P[7][1]*SKK_LOS[7] - P[7][3]*SKK_LOS[6] + P[7][2]*SKK_LOS[9] - P[7][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[7][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[7][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[8] = -SK_LOS[0]*(P[8][0]*SKK_LOS[8] + P[8][1]*SKK_LOS[7] - P[8][3]*SKK_LOS[6] + P[8][2]*SKK_LOS[9] - P[8][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[8][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[8][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[9] = -SK_LOS[0]*(P[9][0]*SKK_LOS[8] + P[9][1]*SKK_LOS[7] - P[9][3]*SKK_LOS[6] + P[9][2]*SKK_LOS[9] - P[9][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[9][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[9][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[10] = -SK_LOS[0]*(P[10][0]*SKK_LOS[8] + P[10][1]*SKK_LOS[7] - P[10][3]*SKK_LOS[6] + P[10][2]*SKK_LOS[9] - P[10][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[10][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[10][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[11] = -SK_LOS[0]*(P[11][0]*SKK_LOS[8] + P[11][1]*SKK_LOS[7] - P[11][3]*SKK_LOS[6] + P[11][2]*SKK_LOS[9] - P[11][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[11][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[11][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[12] = -SK_LOS[0]*(P[12][0]*SKK_LOS[8] + P[12][1]*SKK_LOS[7] - P[12][3]*SKK_LOS[6] + P[12][2]*SKK_LOS[9] - P[12][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[12][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[12][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[13] = 0.0f;//-SK_LOS[0]*(P[13][0]*SKK_LOS[8] + P[13][1]*SKK_LOS[7] - P[13][3]*SKK_LOS[6] + P[13][2]*SKK_LOS[9] - P[13][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[13][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[13][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[14] = -SK_LOS[0]*(P[14][0]*SKK_LOS[8] + P[14][1]*SKK_LOS[7] - P[14][3]*SKK_LOS[6] + P[14][2]*SKK_LOS[9] - P[14][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[14][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[14][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[15] = -SK_LOS[0]*(P[15][0]*SKK_LOS[8] + P[15][1]*SKK_LOS[7] - P[15][3]*SKK_LOS[6] + P[15][2]*SKK_LOS[9] - P[15][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[15][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[15][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[16] = -SK_LOS[0]*(P[16][0]*SKK_LOS[8] + P[16][1]*SKK_LOS[7] - P[16][3]*SKK_LOS[6] + P[16][2]*SKK_LOS[9] - P[16][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[16][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[16][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[17] = -SK_LOS[0]*(P[17][0]*SKK_LOS[8] + P[17][1]*SKK_LOS[7] - P[17][3]*SKK_LOS[6] + P[17][2]*SKK_LOS[9] - P[17][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[17][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[17][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[18] = -SK_LOS[0]*(P[18][0]*SKK_LOS[8] + P[18][1]*SKK_LOS[7] - P[18][3]*SKK_LOS[6] + P[18][2]*SKK_LOS[9] - P[18][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[18][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[18][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[19] = -SK_LOS[0]*(P[19][0]*SKK_LOS[8] + P[19][1]*SKK_LOS[7] - P[19][3]*SKK_LOS[6] + P[19][2]*SKK_LOS[9] - P[19][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[19][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[19][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[20] = -SK_LOS[0]*(P[20][0]*SKK_LOS[8] + P[20][1]*SKK_LOS[7] - P[20][3]*SKK_LOS[6] + P[20][2]*SKK_LOS[9] - P[20][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[20][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[20][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[21] = -SK_LOS[0]*(P[21][0]*SKK_LOS[8] + P[21][1]*SKK_LOS[7] - P[21][3]*SKK_LOS[6] + P[21][2]*SKK_LOS[9] - P[21][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[21][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[21][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + Kfusion[22] = -SK_LOS[0]*(P[22][0]*SKK_LOS[8] + P[22][1]*SKK_LOS[7] - P[22][3]*SKK_LOS[6] + P[22][2]*SKK_LOS[9] - P[22][9]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[2]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[5]*SKK_LOS[14] + P[22][5]*SH_LOS[3]*SKK_LOS[4]*SKK_LOS[14] - P[22][6]*SH_LOS[3]*SKK_LOS[3]*SKK_LOS[14]); + varInnovOptFlow[0] = 1.0f/SK_LOS[0]; + innovOptFlow[0] = losPred[0] - losData[0]; + + // reset the observation index to 0 (we start by fusing the X + // measurement) + obsIndex = 0; + fuseOptFlowData = false; + } + else if (obsIndex == 1) // we are now fusing the Y measurement + { + // Calculate observation jacobians + for (uint8_t i = 0; i < n_states; i++) H_LOS[i] = 0; + H_LOS[0] = SH_LOS[1]*SH_LOS[3]*(2*a1*q1 - 2*q0 + 2*a2*q2) + SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[6] - ve*SH_LOS[11] + vn*SH_LOS[5]); + H_LOS[1] = SH_LOS[1]*SH_LOS[3]*(2*q1 + 2*a1*q0 - 2*a2*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[11] + ve*SH_LOS[6] + vn*SH_LOS[4]); + H_LOS[2] = SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[0]*SH_LOS[3]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6]); + H_LOS[3] = SH_LOS[0]*SH_LOS[3]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11]) - SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1); + H_LOS[4] = SH_LOS[0]*SH_LOS[3]*(a2*(2*q0*q2 + 2*q1*q3) + a3*(2*q0*q3 - 2*q1*q2) - sq(q0) - sq(q1) + sq(q2) + sq(q3)); + H_LOS[5] = -SH_LOS[0]*SH_LOS[3]*(a3*(sq(q0) - sq(q1) + sq(q2) - sq(q3)) + 2*q0*q3 + 2*q1*q2 + a2*(2*q0*q1 - 2*q2*q3)); + H_LOS[6] = SH_LOS[0]*SH_LOS[3]*(a2*(sq(q0) - sq(q1) - sq(q2) + sq(q3)) + 2*q0*q2 - 2*q1*q3 - a3*(2*q0*q1 + 2*q2*q3)); + H_LOS[9] = -SH_LOS[0]*SH_LOS[1]*SH_LOS[7]; + H_LOS[22] = SH_LOS[0]*SH_LOS[1]*SH_LOS[7]; + + // Calculate Kalman gains + SK_LOS[1] = 1/(R_LOS + SKK_LOS[12]*(P[0][2]*SKK_LOS[10] + P[1][2]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[3][2]*SKK_LOS[13] - P[9][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][2]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][2]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][2]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][2]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SKK_LOS[13]*(P[0][3]*SKK_LOS[10] + P[1][3]*SKK_LOS[11] + P[2][3]*SKK_LOS[12] - P[3][3]*SKK_LOS[13] - P[9][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][3]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][3]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][3]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][3]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[10]*(P[0][0]*SKK_LOS[10] + P[1][0]*SKK_LOS[11] + P[2][0]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][0]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][0]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][0]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][0]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][0]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SKK_LOS[11]*(P[0][1]*SKK_LOS[10] + P[1][1]*SKK_LOS[11] + P[2][1]*(SH_LOS[1]*SH_LOS[3]*(2*q2 + 2*a2*q0 + 2*a1*q3) - SH_LOS[3]*SKK_LOS[14]*(vd*SH_LOS[5] + ve*SH_LOS[4] - vn*SH_LOS[6])) - P[3][1]*(SH_LOS[1]*SH_LOS[3]*(2*q3 - 2*a1*q2 + 2*a2*q1) - SH_LOS[3]*SKK_LOS[14]*(ve*SH_LOS[5] - vd*SH_LOS[4] + vn*SH_LOS[11])) - P[9][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][1]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][1]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][1]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][1]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][9]*SKK_LOS[10] + P[1][9]*SKK_LOS[11] + P[2][9]*SKK_LOS[12] - P[3][9]*SKK_LOS[13] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][9]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][9]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][9]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[1]*SH_LOS[7]*SKK_LOS[14]*(P[0][22]*SKK_LOS[10] + P[1][22]*SKK_LOS[11] + P[2][22]*SKK_LOS[12] - P[3][22]*SKK_LOS[13] - P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][22]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][22]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14]*(P[0][4]*SKK_LOS[10] + P[1][4]*SKK_LOS[11] + P[2][4]*SKK_LOS[12] - P[3][4]*SKK_LOS[13] - P[9][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][4]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][4]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) - SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]*(P[0][5]*SKK_LOS[10] + P[1][5]*SKK_LOS[11] + P[2][5]*SKK_LOS[12] - P[3][5]*SKK_LOS[13] - P[9][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][5]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][5]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][5]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]) + SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14]*(P[0][6]*SKK_LOS[10] + P[1][6]*SKK_LOS[11] + P[2][6]*SKK_LOS[12] - P[3][6]*SKK_LOS[13] - P[9][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][6]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14])); + Kfusion[0] = SK_LOS[1]*(P[0][0]*SKK_LOS[10] - P[0][3]*SKK_LOS[13] + P[0][1]*SKK_LOS[11] + P[0][2]*SKK_LOS[12] - P[0][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[0][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[0][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[0][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[1] = SK_LOS[1]*(P[1][0]*SKK_LOS[10] - P[1][3]*SKK_LOS[13] + P[1][1]*SKK_LOS[11] + P[1][2]*SKK_LOS[12] - P[1][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[1][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[1][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[1][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[2] = SK_LOS[1]*(P[2][0]*SKK_LOS[10] - P[2][3]*SKK_LOS[13] + P[2][1]*SKK_LOS[11] + P[2][2]*SKK_LOS[12] - P[2][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[2][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[2][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[2][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[3] = SK_LOS[1]*(P[3][0]*SKK_LOS[10] - P[3][3]*SKK_LOS[13] + P[3][1]*SKK_LOS[11] + P[3][2]*SKK_LOS[12] - P[3][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[3][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[3][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[3][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[4] = SK_LOS[1]*(P[4][0]*SKK_LOS[10] - P[4][3]*SKK_LOS[13] + P[4][1]*SKK_LOS[11] + P[4][2]*SKK_LOS[12] - P[4][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[4][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[4][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[4][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[5] = SK_LOS[1]*(P[5][0]*SKK_LOS[10] - P[5][3]*SKK_LOS[13] + P[5][1]*SKK_LOS[11] + P[5][2]*SKK_LOS[12] - P[5][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[5][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[5][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[5][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[6] = SK_LOS[1]*(P[6][0]*SKK_LOS[10] - P[6][3]*SKK_LOS[13] + P[6][1]*SKK_LOS[11] + P[6][2]*SKK_LOS[12] - P[6][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[6][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[6][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[6][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[7] = SK_LOS[1]*(P[7][0]*SKK_LOS[10] - P[7][3]*SKK_LOS[13] + P[7][1]*SKK_LOS[11] + P[7][2]*SKK_LOS[12] - P[7][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[7][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[7][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[7][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[8] = SK_LOS[1]*(P[8][0]*SKK_LOS[10] - P[8][3]*SKK_LOS[13] + P[8][1]*SKK_LOS[11] + P[8][2]*SKK_LOS[12] - P[8][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[8][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[8][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[8][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[9] = SK_LOS[1]*(P[9][0]*SKK_LOS[10] - P[9][3]*SKK_LOS[13] + P[9][1]*SKK_LOS[11] + P[9][2]*SKK_LOS[12] - P[9][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[9][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[9][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[9][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[10] = SK_LOS[1]*(P[10][0]*SKK_LOS[10] - P[10][3]*SKK_LOS[13] + P[10][1]*SKK_LOS[11] + P[10][2]*SKK_LOS[12] - P[10][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[10][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[10][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[10][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[11] = SK_LOS[1]*(P[11][0]*SKK_LOS[10] - P[11][3]*SKK_LOS[13] + P[11][1]*SKK_LOS[11] + P[11][2]*SKK_LOS[12] - P[11][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[11][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[11][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[11][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[12] = SK_LOS[1]*(P[12][0]*SKK_LOS[10] - P[12][3]*SKK_LOS[13] + P[12][1]*SKK_LOS[11] + P[12][2]*SKK_LOS[12] - P[12][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[12][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[12][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[12][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[13] = 0.0f;//SK_LOS[1]*(P[13][0]*SKK_LOS[10] - P[13][3]*SKK_LOS[13] + P[13][1]*SKK_LOS[11] + P[13][2]*SKK_LOS[12] - P[13][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[13][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[13][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[13][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[14] = SK_LOS[1]*(P[14][0]*SKK_LOS[10] - P[14][3]*SKK_LOS[13] + P[14][1]*SKK_LOS[11] + P[14][2]*SKK_LOS[12] - P[14][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[14][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[14][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[14][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[15] = SK_LOS[1]*(P[15][0]*SKK_LOS[10] - P[15][3]*SKK_LOS[13] + P[15][1]*SKK_LOS[11] + P[15][2]*SKK_LOS[12] - P[15][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[15][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[15][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[15][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[16] = SK_LOS[1]*(P[16][0]*SKK_LOS[10] - P[16][3]*SKK_LOS[13] + P[16][1]*SKK_LOS[11] + P[16][2]*SKK_LOS[12] - P[16][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[16][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[16][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[16][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[17] = SK_LOS[1]*(P[17][0]*SKK_LOS[10] - P[17][3]*SKK_LOS[13] + P[17][1]*SKK_LOS[11] + P[17][2]*SKK_LOS[12] - P[17][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[17][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[17][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[17][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[18] = SK_LOS[1]*(P[18][0]*SKK_LOS[10] - P[18][3]*SKK_LOS[13] + P[18][1]*SKK_LOS[11] + P[18][2]*SKK_LOS[12] - P[18][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[18][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[18][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[18][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[19] = SK_LOS[1]*(P[19][0]*SKK_LOS[10] - P[19][3]*SKK_LOS[13] + P[19][1]*SKK_LOS[11] + P[19][2]*SKK_LOS[12] - P[19][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[19][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[19][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[19][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[20] = SK_LOS[1]*(P[20][0]*SKK_LOS[10] - P[20][3]*SKK_LOS[13] + P[20][1]*SKK_LOS[11] + P[20][2]*SKK_LOS[12] - P[20][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[20][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[20][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[20][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[21] = SK_LOS[1]*(P[21][0]*SKK_LOS[10] - P[21][3]*SKK_LOS[13] + P[21][1]*SKK_LOS[11] + P[21][2]*SKK_LOS[12] - P[21][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[21][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[21][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[21][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + Kfusion[22] = SK_LOS[1]*(P[22][0]*SKK_LOS[10] - P[22][3]*SKK_LOS[13] + P[22][1]*SKK_LOS[11] + P[22][2]*SKK_LOS[12] - P[22][9]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][22]*SH_LOS[1]*SH_LOS[7]*SKK_LOS[14] + P[22][6]*SH_LOS[3]*SKK_LOS[0]*SKK_LOS[14] + P[22][4]*SH_LOS[3]*SKK_LOS[2]*SKK_LOS[14] - P[22][5]*SH_LOS[3]*SKK_LOS[1]*SKK_LOS[14]); + varInnovOptFlow[1] = 1.0f/SK_LOS[1]; + innovOptFlow[1] = losPred[1] - losData[1]; + } + + // Check the innovation for consistency and don't fuse if > 3Sigma + if ((innovOptFlow[obsIndex]*innovOptFlow[obsIndex]/varInnovOptFlow[obsIndex]) < 9.0f) + { + // correct the state vector + for (uint8_t j = 0; j < n_states; j++) + { + states[j] = states[j] - Kfusion[j] * innovOptFlow[obsIndex]; + } + // normalise the quaternion states + float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]); + if (quatMag > 1e-12) + { + for (uint8_t j= 0; j<=3; j++) + { + float quatMagInv = 1.0f/quatMag; + states[j] = states[j] * quatMagInv; + } + } + // correct the covariance P = (I - K*H)*P + // take advantage of the empty columns in KH to reduce the + // number of operations + for (uint8_t i = 0; i < n_states; i++) + { + for (uint8_t j = 0; j <= 6; j++) + { + KH[i][j] = Kfusion[i] * H_LOS[j]; + } + for (uint8_t j = 7; j <= 8; j++) + { + KH[i][j] = 0.0f; + } + KH[i][9] = Kfusion[i] * H_LOS[9]; + for (uint8_t j = 10; j <= 21; j++) + { + KH[i][j] = 0.0f; + } + KH[i][22] = Kfusion[i] * H_LOS[22]; + } + for (uint8_t i = 0; i < n_states; i++) + { + for (uint8_t j = 0; j < n_states; j++) + { + KHP[i][j] = 0.0f; + for (uint8_t k = 0; k <= 6; k++) + { + KHP[i][j] = KHP[i][j] + KH[i][k] * P[k][j]; + } + KHP[i][j] = KHP[i][j] + KH[i][9] * P[9][j]; + KHP[i][j] = KHP[i][j] + KH[i][22] * P[2][j]; + } + } + } + for (uint8_t i = 0; i < n_states; i++) + { + for (uint8_t j = 0; j < n_states; j++) + { + P[i][j] = P[i][j] - KHP[i][j]; + } + } + } + obsIndex = obsIndex + 1; + ForceSymmetry(); + ConstrainVariances(); +} + void AttPosEKF::zeroCols(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last) { uint8_t row; @@ -1904,6 +2214,24 @@ void AttPosEKF::OnGroundCheck() if (staticMode) { staticMode = (!refSet || (GPSstatus < GPS_FIX_3D)); } + // don't update wind states if there is no airspeed measurement + if (onGround || !useAirspeed) { + inhibitWindStates = true; + } else { + inhibitWindStates =false; + } + // don't update magnetic field states if on ground or not using compass + if (onGround || !useCompass) { + inhibitMagStates = true; + } else { + inhibitMagStates = false; + } + // don't update terrain offset state if on ground + if (onGround) { + inhibitGndHgtState = true; + } else { + inhibitGndHgtState = false; + } } void AttPosEKF::calcEarthRateNED(Vector3f &omega, float latitude) @@ -1931,8 +2259,8 @@ void AttPosEKF::CovarianceInit() P[11][11] = P[10][10]; P[12][12] = P[10][10]; P[13][13] = sq(0.2f*dtIMU); - P[14][14] = sq(8.0f); - P[15][14] = P[14][14]; + P[14][14] = sq(0.0f); + P[15][15] = P[14][14]; P[16][16] = sq(0.02f); P[17][17] = P[16][16]; P[18][18] = P[16][16]; diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.h b/src/modules/ekf_att_pos_estimator/estimator_23states.h index dc461cfa1..3110266ce 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.h +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.h @@ -29,6 +29,10 @@ public: float covDelAngMax; // maximum delta angle between covariance predictions float rngFinderPitch; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis. + float a1; // optical flow sensor misalgnment angle about X axis (rad) + float a2; // optical flow sensor misalgnment angle about Y axis (rad) + float a3; // optical flow sensor misalgnment angle about Z axis (rad) + float yawVarScale; float windVelSigma; float dAngBiasSigma; @@ -55,6 +59,9 @@ public: covDelAngMax = 0.02f; // maximum delta angle between covariance predictions rngFinderPitch = 0.0f; // pitch angle of laser range finder in radians. Zero is aligned with the Z body axis. Positive is RH rotation about Y body axis. EAS2TAS = 1.0f; + a1 = 0.0f; // optical flow sensor misalgnment angle about X axis (rad) + a2 = 0.0f; // optical flow sensor misalgnment angle about Y axis (rad) + a3 = 0.0f; // optical flow sensor misalgnment angle about Z axis (rad) yawVarScale = 1.0f; windVelSigma = 0.1f; @@ -115,6 +122,7 @@ public: float statesAtMagMeasTime[n_states]; // filter satates at the effective measurement time float statesAtVtasMeasTime[n_states]; // filter states at the effective measurement time float statesAtRngTime[n_states]; // filter states at the effective measurement time + float statesAtOptFlowTime[n_states]; // States at the effective optical flow measurement time Vector3f correctedDelAng; // delta angles about the xyz body axes corrected for errors (rad) Vector3f correctedDelVel; // delta velocities along the XYZ body axes corrected for errors (m/s) @@ -147,9 +155,13 @@ public: float innovMag[3]; // innovation output float varInnovMag[3]; // innovation variance output Vector3f magData; // magnetometer flux radings in X,Y,Z body axes + float losData[2]; // optical flow LOS rate measurements (rad/sec) float innovVtas; // innovation output float innovRng; ///< Range finder innovation + float innovOptFlow[2]; // optical flow LOS innovations (rad/sec) + float varInnovOptFlow[2]; // optical flow innovations variances (rad/sec)^2 float varInnovVtas; // innovation variance output + float varInnovRng; // range finder innovation variance float VtasMeas; // true airspeed measurement (m/s) float magDeclination; ///< magnetic declination double latRef; // WGS-84 latitude of reference point (rad) @@ -178,12 +190,18 @@ public: bool fuseMagData; // boolean true when magnetometer data is to be fused bool fuseVtasData; // boolean true when airspeed data is to be fused bool fuseRngData; ///< true when range data is fused + bool fuseOptFlowData; // true when optical flow data is fused + + bool inhibitWindStates; // true when wind states and covariances are to remain constant + bool inhibitMagStates; // true when magnetic field states and covariances are to remain constant + bool inhibitGndHgtState; // true when the terrain ground height offset state and covariances are to remain constant bool onGround; ///< boolean true when the flight vehicle is on the ground (not flying) bool staticMode; ///< boolean true if no position feedback is fused bool useAirspeed; ///< boolean true if airspeed data is being used bool useCompass; ///< boolean true if magnetometer data is being used bool useRangeFinder; ///< true when rangefinder is being used + bool useOpticalFlow; // true when optical flow data is being used bool ekfDiverged; uint64_t lastReset; @@ -208,7 +226,7 @@ void FuseAirspeed(); void FuseRangeFinder(); -void FuseOpticalFlow(); +void FuseOptFlow(); void zeroRows(float (&covMat)[n_states][n_states], uint8_t first, uint8_t last); diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp index b4767a0d3..24168b84c 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp @@ -101,6 +101,25 @@ Vector3f operator*( Mat3f matIn, Vector3f vecIn) return vecOut; } +// overload * operator to provide a matrix product +Mat3f operator*( Mat3f matIn1, Mat3f matIn2) +{ + Mat3f matOut; + matOut.x.x = matIn1.x.x*matIn2.x.x + matIn1.x.y*matIn2.y.x + matIn1.x.z*matIn2.z.x; + matOut.x.y = matIn1.x.x*matIn2.x.y + matIn1.x.y*matIn2.y.y + matIn1.x.z*matIn2.z.y; + matOut.x.z = matIn1.x.x*matIn2.x.z + matIn1.x.y*matIn2.y.z + matIn1.x.z*matIn2.z.z; + + matOut.y.x = matIn1.y.x*matIn2.x.x + matIn1.y.y*matIn2.y.x + matIn1.y.z*matIn2.z.x; + matOut.y.y = matIn1.y.x*matIn2.x.y + matIn1.y.y*matIn2.y.y + matIn1.y.z*matIn2.z.y; + matOut.y.z = matIn1.y.x*matIn2.x.z + matIn1.y.y*matIn2.y.z + matIn1.y.z*matIn2.z.z; + + matOut.z.x = matIn1.z.x*matIn2.x.x + matIn1.z.y*matIn2.y.x + matIn1.z.z*matIn2.z.x; + matOut.z.y = matIn1.z.x*matIn2.x.y + matIn1.z.y*matIn2.y.y + matIn1.z.z*matIn2.z.y; + matOut.z.z = matIn1.z.x*matIn2.x.z + matIn1.z.y*matIn2.y.z + matIn1.z.z*matIn2.z.z; + + return matOut; +} + // overload % operator to provide a vector cross product Vector3f operator%( Vector3f vecIn1, Vector3f vecIn2) { diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.h b/src/modules/ekf_att_pos_estimator/estimator_utilities.h index d47568b62..5648cb05c 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_utilities.h +++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.h @@ -41,6 +41,7 @@ Vector3f operator*(float sclIn1, Vector3f vecIn1); Vector3f operator+( Vector3f vecIn1, Vector3f vecIn2); Vector3f operator-( Vector3f vecIn1, Vector3f vecIn2); Vector3f operator*( Mat3f matIn, Vector3f vecIn); +Mat3f operator*( Mat3f matIn1, Mat3f matIn2); Vector3f operator%( Vector3f vecIn1, Vector3f vecIn2); Vector3f operator*(Vector3f vecIn1, float sclIn1); @@ -79,4 +80,4 @@ struct ekf_status_report { bool velOffsetExcessive; }; -void ekf_debug(const char *fmt, ...); \ No newline at end of file +void ekf_debug(const char *fmt, ...); -- cgit v1.2.3 From 0bf9c2a9b262a4c8569031f0f7e9ded432d2d4b3 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 29 Jun 2014 14:09:22 +0200 Subject: navigator: API changes, reparing to move manual modes to navigator, WIP --- src/modules/navigator/loiter.cpp | 21 ++++++++----- src/modules/navigator/loiter.h | 4 +-- src/modules/navigator/mission.cpp | 42 ++++++++++++------------- src/modules/navigator/mission.h | 6 ++-- src/modules/navigator/mission_block.cpp | 53 +++++++++++++++----------------- src/modules/navigator/mission_block.h | 4 +-- src/modules/navigator/navigator.h | 4 ++- src/modules/navigator/navigator_main.cpp | 11 ++++--- src/modules/navigator/navigator_mode.cpp | 19 ++++++------ src/modules/navigator/navigator_mode.h | 9 ++---- 10 files changed, 87 insertions(+), 86 deletions(-) diff --git a/src/modules/navigator/loiter.cpp b/src/modules/navigator/loiter.cpp index 5e7067b0e..f827e70c9 100644 --- a/src/modules/navigator/loiter.cpp +++ b/src/modules/navigator/loiter.cpp @@ -36,6 +36,7 @@ * Helper class to loiter * * @author Julian Oes + * @author Anton Babushkin */ #include @@ -51,14 +52,13 @@ #include #include "loiter.h" +#include "navigator.h" Loiter::Loiter(Navigator *navigator, const char *name) : MissionBlock(navigator, name) { /* load initial params */ updateParams(); - /* initial reset */ - on_inactive(); } Loiter::~Loiter() @@ -71,16 +71,23 @@ Loiter::on_inactive() } void -Loiter::on_activation(struct position_setpoint_triplet_s *pos_sp_triplet) +Loiter::on_activation() { - set_loiter_item(pos_sp_triplet); + /* set current mission item to loiter */ + set_loiter_item(&_mission_item); + + /* convert mission item to current setpoint */ + struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); pos_sp_triplet->previous.valid = false; mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); pos_sp_triplet->next.valid = false; + + _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == SETPOINT_TYPE_LOITER); + + _navigator->set_position_setpoint_triplet_updated(); } -bool -Loiter::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) +void +Loiter::on_active() { - return false; } diff --git a/src/modules/navigator/loiter.h b/src/modules/navigator/loiter.h index 5ce86d2a7..37ab57a07 100644 --- a/src/modules/navigator/loiter.h +++ b/src/modules/navigator/loiter.h @@ -56,9 +56,9 @@ public: virtual void on_inactive(); - virtual void on_activation(struct position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_activation(); - virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_active(); }; #endif diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index ab99a6b7e..1e86b1b6c 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -54,8 +54,8 @@ #include #include -#include "navigator.h" #include "mission.h" +#include "navigator.h" Mission::Mission(Navigator *navigator, const char *name) : MissionBlock(navigator, name), @@ -97,16 +97,14 @@ Mission::on_inactive() } void -Mission::on_activation(struct position_setpoint_triplet_s *pos_sp_triplet) +Mission::on_activation() { - set_mission_items(pos_sp_triplet); + set_mission_items(); } -bool -Mission::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) +void +Mission::on_active() { - bool updated = false; - /* check if anything has changed */ bool onboard_updated; orb_check(_navigator->get_onboard_mission_sub(), &onboard_updated); @@ -122,18 +120,18 @@ Mission::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) /* reset mission items if needed */ if (onboard_updated || offboard_updated) { - set_mission_items(pos_sp_triplet); - updated = true; + set_mission_items(); + + _navigator->set_position_setpoint_triplet_updated(); } /* lets check if we reached the current mission item */ if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) { advance_mission(); - set_mission_items(pos_sp_triplet); - updated = true; - } + set_mission_items(); - return updated; + _navigator->set_position_setpoint_triplet_updated(); + } } void @@ -223,8 +221,10 @@ Mission::advance_mission() } void -Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet) +Mission::set_mission_items() { + struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); + set_previous_pos_setpoint(pos_sp_triplet); /* try setting onboard mission item */ @@ -235,7 +235,7 @@ Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet) "#audio: onboard mission running"); } _mission_type = MISSION_TYPE_ONBOARD; - _navigator->set_can_loiter_at_sp(false); + _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached); /* try setting offboard mission item */ } else if (is_current_offboard_mission_item_set(&pos_sp_triplet->current)) { @@ -245,7 +245,8 @@ Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet) "#audio: offboard mission running"); } _mission_type = MISSION_TYPE_OFFBOARD; - _navigator->set_can_loiter_at_sp(false); + _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached); + } else { if (_mission_type != MISSION_TYPE_NONE) { mavlink_log_info(_navigator->get_mavlink_fd(), @@ -255,12 +256,15 @@ Mission::set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet) "#audio: no mission available"); } _mission_type = MISSION_TYPE_NONE; + _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached); - set_loiter_item(pos_sp_triplet); + set_loiter_item(&_mission_item); + pos_sp_triplet->previous.valid = false; mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); pos_sp_triplet->next.valid = false; + reset_mission_item_reached(); report_mission_finished(); } @@ -279,7 +283,6 @@ Mission::is_current_onboard_mission_item_set(struct position_setpoint_s *current &new_mission_item)) { /* convert the current mission item and set it valid */ mission_item_to_position_setpoint(&new_mission_item, current_pos_sp); - current_pos_sp->valid = true; reset_mission_item_reached(); @@ -306,7 +309,6 @@ Mission::is_current_offboard_mission_item_set(struct position_setpoint_s *curren if (read_mission_item(dm_current, true, &_current_offboard_mission_index, &new_mission_item)) { /* convert the current mission item and set it valid */ mission_item_to_position_setpoint(&new_mission_item, current_pos_sp); - current_pos_sp->valid = true; reset_mission_item_reached(); @@ -330,7 +332,6 @@ Mission::get_next_onboard_mission_item(struct position_setpoint_s *next_pos_sp) if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, false, &next_temp_mission_index, &new_mission_item)) { /* convert next mission item to position setpoint */ mission_item_to_position_setpoint(&new_mission_item, next_pos_sp); - next_pos_sp->valid = true; return; } } @@ -358,7 +359,6 @@ Mission::get_next_offboard_mission_item(struct position_setpoint_s *next_pos_sp) if (read_mission_item(dm_current, false, &next_temp_mission_index, &new_mission_item)) { /* convert next mission item to position setpoint */ mission_item_to_position_setpoint(&new_mission_item, next_pos_sp); - next_pos_sp->valid = true; return; } } diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index 38a4f7612..ac293990f 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -71,9 +71,9 @@ public: virtual void on_inactive(); - virtual void on_activation(struct position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_activation(); - virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_active(); private: /** @@ -94,7 +94,7 @@ private: /** * Set new mission items */ - void set_mission_items(struct position_setpoint_triplet_s *pos_sp_triplet); + void set_mission_items(); /** * Try to set the current position setpoint from an onboard mission item diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index acf3ad569..bf3c934a6 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -58,8 +58,7 @@ MissionBlock::MissionBlock(Navigator *navigator, const char *name) : _waypoint_position_reached(false), _waypoint_yaw_reached(false), _time_first_inside_orbit(0), - _mission_item({0}), - _mission_item_valid(false) + _mission_item({0}) { } @@ -70,6 +69,10 @@ MissionBlock::~MissionBlock() bool MissionBlock::is_mission_item_reached() { + if (_mission_item.nav_cmd == NAV_CMD_IDLE) { + return false; + } + if (_mission_item.nav_cmd == NAV_CMD_LAND) { return _navigator->get_vstatus()->condition_landed; } @@ -83,7 +86,6 @@ MissionBlock::is_mission_item_reached() hrt_abstime now = hrt_absolute_time(); if (!_waypoint_position_reached) { - float dist = -1.0f; float dist_xy = -1.0f; float dist_z = -1.0f; @@ -209,43 +211,38 @@ MissionBlock::set_previous_pos_setpoint(struct position_setpoint_triplet_s *pos_ } void -MissionBlock::set_loiter_item(struct position_setpoint_triplet_s *pos_sp_triplet) +MissionBlock::set_loiter_item(struct mission_item_s *item) { if (_navigator->get_vstatus()->condition_landed) { /* landed, don't takeoff, but switch to IDLE mode */ - _mission_item.nav_cmd = NAV_CMD_IDLE; - - _navigator->set_can_loiter_at_sp(false); - - mavlink_log_info(_navigator->get_mavlink_fd(), "landed, switch to IDLE"); + item->nav_cmd = NAV_CMD_IDLE; } else { - _mission_item.nav_cmd = NAV_CMD_LOITER_UNLIMITED; + item->nav_cmd = NAV_CMD_LOITER_UNLIMITED; + + struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); if (_navigator->get_can_loiter_at_sp() && pos_sp_triplet->current.valid) { /* use current position setpoint */ - _mission_item.lat = pos_sp_triplet->current.lat; - _mission_item.lon = pos_sp_triplet->current.lon; - _mission_item.altitude = pos_sp_triplet->current.alt; + item->lat = pos_sp_triplet->current.lat; + item->lon = pos_sp_triplet->current.lon; + item->altitude = pos_sp_triplet->current.alt; } else { /* use current position */ - _mission_item.lat = _navigator->get_global_position()->lat; - _mission_item.lon = _navigator->get_global_position()->lon; - _mission_item.altitude = _navigator->get_global_position()->alt; + item->lat = _navigator->get_global_position()->lat; + item->lon = _navigator->get_global_position()->lon; + item->altitude = _navigator->get_global_position()->alt; } - _mission_item.altitude_is_relative = false; - _mission_item.yaw = NAN; - _mission_item.loiter_radius = _navigator->get_loiter_radius(); - _mission_item.loiter_direction = 1; - _mission_item.acceptance_radius = _navigator->get_acceptance_radius(); - _mission_item.time_inside = 0.0f; - _mission_item.pitch_min = 0.0f; - _mission_item.autocontinue = false; - _mission_item.origin = ORIGIN_ONBOARD; - - _navigator->set_can_loiter_at_sp(true); - mavlink_log_info(_navigator->get_mavlink_fd(), "switch to LOITER"); + item->altitude_is_relative = false; + item->yaw = NAN; + item->loiter_radius = _navigator->get_loiter_radius(); + item->loiter_direction = 1; + item->acceptance_radius = _navigator->get_acceptance_radius(); + item->time_inside = 0.0f; + item->pitch_min = 0.0f; + item->autocontinue = false; + item->origin = ORIGIN_ONBOARD; } } diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h index 4f79238f4..22f42cc31 100644 --- a/src/modules/navigator/mission_block.h +++ b/src/modules/navigator/mission_block.h @@ -91,11 +91,9 @@ protected: /** * Set a loiter mission item, if possible reuse the position setpoint, otherwise take the current position */ - // TODO remove argument, get position setpoint from navigator, add to arguments pointer to mission item instead - void set_loiter_item(struct position_setpoint_triplet_s *pos_sp_triplet); + void set_loiter_item(struct mission_item_s *item); mission_item_s _mission_item; - bool _mission_item_valid; bool _waypoint_position_reached; bool _waypoint_yaw_reached; hrt_abstime _time_first_inside_orbit; diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index 184ecd365..5dcd8859e 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -103,6 +103,7 @@ public: * Setters */ void set_can_loiter_at_sp(bool can_loiter) { _can_loiter_at_sp = can_loiter; } + void set_position_setpoint_triplet_updated() { _pos_sp_triplet_updated = true; } /** * Getters @@ -110,6 +111,7 @@ public: struct vehicle_status_s* get_vstatus() { return &_vstatus; } struct vehicle_global_position_s* get_global_position() { return &_global_pos; } struct home_position_s* get_home_position() { return &_home_pos; } + struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; } int get_onboard_mission_sub() { return _onboard_mission_sub; } int get_offboard_mission_sub() { return _offboard_mission_sub; } Geofence& get_geofence() { return _geofence; } @@ -162,7 +164,7 @@ private: NavigatorMode *_navigation_mode_array[NAVIGATOR_MODE_ARRAY_SIZE]; /**< array of navigation modes */ bool _can_loiter_at_sp; /**< flags if current position SP can be used to loiter */ - bool _update_triplet; /**< flags if position SP triplet needs to be published */ + bool _pos_sp_triplet_updated; /**< flags if position SP triplet needs to be published */ control::BlockParamFloat _param_loiter_radius; /**< loiter radius for fixedwing */ control::BlockParamFloat _param_acceptance_radius; /**< acceptance for takeoff */ diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 266114e38..bb48db829 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -121,7 +121,7 @@ Navigator::Navigator() : _mission(this, "MIS"), _loiter(this, "LOI"), _rtl(this, "RTL"), - _update_triplet(false), + _pos_sp_triplet_updated(false), _param_loiter_radius(this, "LOITER_RAD"), _param_acceptance_radius(this, "ACC_RAD") { @@ -371,20 +371,21 @@ Navigator::task_main() /* iterate through navigation modes and set active/inactive for each */ for(unsigned int i = 0; i < NAVIGATOR_MODE_ARRAY_SIZE; i++) { - _update_triplet = _navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i], &_pos_sp_triplet); + _navigation_mode_array[i]->run(_navigation_mode == _navigation_mode_array[i]); } /* if nothing is running, set position setpoint triplet invalid */ if (_navigation_mode == nullptr) { + // TODO publish empty sp only once _pos_sp_triplet.previous.valid = false; _pos_sp_triplet.current.valid = false; _pos_sp_triplet.next.valid = false; - _update_triplet = true; + _pos_sp_triplet_updated = true; } - if (_update_triplet) { + if (_pos_sp_triplet_updated) { publish_position_setpoint_triplet(); - _update_triplet = false; + _pos_sp_triplet_updated = false; } perf_end(_loop_perf); diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp index 6361ea9c8..f43215665 100644 --- a/src/modules/navigator/navigator_mode.cpp +++ b/src/modules/navigator/navigator_mode.cpp @@ -40,6 +40,7 @@ */ #include "navigator_mode.h" +#include "navigator.h" NavigatorMode::NavigatorMode(Navigator *navigator, const char *name) : SuperBlock(NULL, name), @@ -56,18 +57,17 @@ NavigatorMode::~NavigatorMode() { } -bool -NavigatorMode::run(bool active, struct position_setpoint_triplet_s *pos_sp_triplet) { +void +NavigatorMode::run(bool active) { if (active) { if (_first_run) { /* first run */ _first_run = false; - on_activation(pos_sp_triplet); - return true; + on_activation(); } else { /* periodic updates when active */ - on_active(pos_sp_triplet); + on_active(); } } else { @@ -83,14 +83,13 @@ NavigatorMode::on_inactive() } void -NavigatorMode::on_activation(struct position_setpoint_triplet_s *pos_sp_triplet) +NavigatorMode::on_activation() { /* invalidate position setpoint by default */ - pos_sp_triplet->current.valid = false; + _navigator->get_position_setpoint_triplet()->current.valid = false; } -bool -NavigatorMode::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) +void +NavigatorMode::on_active() { - return false; } diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h index 5c36af1fe..a7ba79bba 100644 --- a/src/modules/navigator/navigator_mode.h +++ b/src/modules/navigator/navigator_mode.h @@ -66,7 +66,7 @@ public: */ virtual ~NavigatorMode(); - bool run(bool active, struct position_setpoint_triplet_s *pos_sp_triplet); + void run(bool active); /** * This function is called while the mode is inactive @@ -76,15 +76,12 @@ public: /** * This function is called one time when mode become active, poos_sp_triplet must be initialized here */ - virtual void on_activation(struct position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_activation(); /** * This function is called while the mode is active - * - * @param position setpoint triplet to set - * @return true if position setpoint triplet has been changed */ - virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_active(); protected: Navigator *_navigator; -- cgit v1.2.3 From adf230ce4efe30087e751f143dab1df33a7d3b70 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 29 Jun 2014 15:35:34 +0200 Subject: navigator: more API changes, duplicate code removed --- src/modules/navigator/mission.cpp | 166 ++++++++++++++------------------ src/modules/navigator/mission.h | 10 +- src/modules/navigator/mission_block.cpp | 5 +- src/modules/navigator/mission_block.h | 2 +- src/modules/navigator/rtl.cpp | 25 ++--- src/modules/navigator/rtl.h | 6 +- 6 files changed, 95 insertions(+), 119 deletions(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 1e86b1b6c..fbfd1259d 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -225,29 +225,27 @@ Mission::set_mission_items() { struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); - set_previous_pos_setpoint(pos_sp_triplet); + /* set previous position setpoint to current */ + set_previous_pos_setpoint(); /* try setting onboard mission item */ - if (is_current_onboard_mission_item_set(&pos_sp_triplet->current)) { + if (set_mission_item(true, false, &_mission_item)) { /* if mission type changed, notify */ if (_mission_type != MISSION_TYPE_ONBOARD) { - mavlink_log_info(_navigator->get_mavlink_fd(), - "#audio: onboard mission running"); + mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: onboard mission running"); } _mission_type = MISSION_TYPE_ONBOARD; - _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached); /* try setting offboard mission item */ - } else if (is_current_offboard_mission_item_set(&pos_sp_triplet->current)) { + } else if (set_mission_item(false, false, &_mission_item)) { /* if mission type changed, notify */ if (_mission_type != MISSION_TYPE_OFFBOARD) { - mavlink_log_info(_navigator->get_mavlink_fd(), - "#audio: offboard mission running"); + mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: offboard mission running"); } _mission_type = MISSION_TYPE_OFFBOARD; - _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached); } else { + /* no mission available, switch to loiter */ if (_mission_type != MISSION_TYPE_NONE) { mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: mission finished"); @@ -257,126 +255,108 @@ Mission::set_mission_items() } _mission_type = MISSION_TYPE_NONE; - _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.valid && _waypoint_position_reached); - + /* set loiter mission item */ set_loiter_item(&_mission_item); + /* update position setpoint triplet */ pos_sp_triplet->previous.valid = false; mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); pos_sp_triplet->next.valid = false; + _navigator->set_can_loiter_at_sp(pos_sp_triplet->current.type == SETPOINT_TYPE_LOITER); + reset_mission_item_reached(); report_mission_finished(); + + _navigator->set_position_setpoint_triplet_updated(); + return; } -} -bool -Mission::is_current_onboard_mission_item_set(struct position_setpoint_s *current_pos_sp) -{ - /* make sure param is up to date */ - updateParams(); - if (_param_onboard_enabled.get() > 0 && - _current_onboard_mission_index >= 0&& - _current_onboard_mission_index < (int)_onboard_mission.count) { - struct mission_item_s new_mission_item; - if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, true, &_current_onboard_mission_index, - &new_mission_item)) { - /* convert the current mission item and set it valid */ - mission_item_to_position_setpoint(&new_mission_item, current_pos_sp); + /* new current mission item set */ + mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); + _navigator->set_can_loiter_at_sp(false); + reset_mission_item_reached(); + + if (_mission_type == MISSION_TYPE_OFFBOARD) { + report_current_offboard_mission_item(); + } + // TODO: report onboard mission item somehow - reset_mission_item_reached(); + /* try to read next mission item */ + struct mission_item_s mission_item_next; + if (!set_mission_item(_mission_type == MISSION_TYPE_ONBOARD, true, &mission_item_next)) { + /* got next mission item, update setpoint triplet */ + mission_item_to_position_setpoint(&mission_item_next, &pos_sp_triplet->next); - /* TODO: report this somehow */ - memcpy(&_mission_item, &new_mission_item, sizeof(struct mission_item_s)); - return true; - } + } else { + /* next mission item is not available */ + pos_sp_triplet->next.valid = false; } - return false; + + _navigator->set_position_setpoint_triplet_updated(); } bool -Mission::is_current_offboard_mission_item_set(struct position_setpoint_s *current_pos_sp) +Mission::set_mission_item(bool onboard, bool next_item, struct mission_item_s *mission_item) { - if (_current_offboard_mission_index >= 0 && - _current_offboard_mission_index < (int)_offboard_mission.count) { - dm_item_t dm_current; - if (_offboard_mission.dataman_id == 0) { - dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0; - } else { - dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1; - } - struct mission_item_s new_mission_item; - if (read_mission_item(dm_current, true, &_current_offboard_mission_index, &new_mission_item)) { - /* convert the current mission item and set it valid */ - mission_item_to_position_setpoint(&new_mission_item, current_pos_sp); + /* make sure param is up to date */ + updateParams(); - reset_mission_item_reached(); + /* select onboard/offboard mission */ + int *mission_index_ptr; + struct mission_s *mission; + dm_item_t dm_item; + int mission_index_next; - report_current_offboard_mission_item(); - memcpy(&_mission_item, &new_mission_item, sizeof(struct mission_item_s)); - return true; + if (onboard) { + /* onboard mission */ + if (!_param_onboard_enabled.get()) { + return false; } - } - return false; -} -void -Mission::get_next_onboard_mission_item(struct position_setpoint_s *next_pos_sp) -{ - int next_temp_mission_index = _onboard_mission.current_index + 1; + mission_index_next = _current_onboard_mission_index + 1; + mission_index_ptr = next_item ? &mission_index_next : &_current_onboard_mission_index; - /* try if there is a next onboard mission */ - if (_onboard_mission.current_index >= 0 && - next_temp_mission_index < (int)_onboard_mission.count) { - struct mission_item_s new_mission_item; - if (read_mission_item(DM_KEY_WAYPOINTS_ONBOARD, false, &next_temp_mission_index, &new_mission_item)) { - /* convert next mission item to position setpoint */ - mission_item_to_position_setpoint(&new_mission_item, next_pos_sp); - return; - } - } + mission = &_onboard_mission; - /* give up */ - next_pos_sp->valid = false; - return; -} + dm_item = DM_KEY_WAYPOINTS_ONBOARD; + + } else { + /* offboard mission */ + mission_index_next = _current_offboard_mission_index + 1; + mission_index_ptr = next_item ? &mission_index_next : &_current_offboard_mission_index; + + mission = &_offboard_mission; -void -Mission::get_next_offboard_mission_item(struct position_setpoint_s *next_pos_sp) -{ - /* try if there is a next offboard mission */ - int next_temp_mission_index = _offboard_mission.current_index + 1; - warnx("next index: %d, count; %d", next_temp_mission_index, _offboard_mission.count); - if (_offboard_mission.current_index >= 0 && - next_temp_mission_index < (int)_offboard_mission.count) { - dm_item_t dm_current; if (_offboard_mission.dataman_id == 0) { - dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0; + dm_item = DM_KEY_WAYPOINTS_OFFBOARD_0; + } else { - dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1; + dm_item = DM_KEY_WAYPOINTS_OFFBOARD_1; } + } + + if (*mission_index_ptr >= 0 && *mission_index_ptr < (int)mission->count) { struct mission_item_s new_mission_item; - if (read_mission_item(dm_current, false, &next_temp_mission_index, &new_mission_item)) { - /* convert next mission item to position setpoint */ - mission_item_to_position_setpoint(&new_mission_item, next_pos_sp); - return; + + if (read_mission_item(dm_item, true, mission_index_ptr, &new_mission_item)) { + memcpy(&mission_item, &new_mission_item, sizeof(struct mission_item_s)); + return true; } } - /* give up */ - next_pos_sp->valid = false; - return; + return false; } bool -Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index, +Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index_ptr, struct mission_item_s *new_mission_item) { /* repeat several to get the mission item because we might have to follow multiple DO_JUMPS */ - for (int i=0; i<10; i++) { + for (int i = 0; i < 10; i++) { const ssize_t len = sizeof(struct mission_item_s); /* read mission item from datamanager */ - if (dm_read(dm_item, *mission_index, new_mission_item, len) != len) { + if (dm_read(dm_item, *mission_index_ptr, new_mission_item, len) != len) { /* not supposed to happen unless the datamanager can't access the SD card, etc. */ mavlink_log_critical(_navigator->get_mavlink_fd(), "#audio: ERROR waypoint could not be read"); @@ -394,7 +374,7 @@ Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *missio if (is_current) { (new_mission_item->do_jump_current_count)++; /* save repeat count */ - if (dm_write(dm_item, *mission_index, DM_PERSIST_IN_FLIGHT_RESET, + if (dm_write(dm_item, *mission_index_ptr, DM_PERSIST_IN_FLIGHT_RESET, new_mission_item, len) != len) { /* not supposed to happen unless the datamanager can't access the * dataman */ @@ -405,12 +385,12 @@ Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *missio } /* set new mission item index and repeat * we don't have to validate here, if it's invalid, we should realize this later .*/ - *mission_index = new_mission_item->do_jump_mission_index; + *mission_index_ptr = new_mission_item->do_jump_mission_index; } else { mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: DO JUMP repetitions completed"); /* no more DO_JUMPS, therefore just try to continue with next mission item */ - (*mission_index)++; + (*mission_index_ptr)++; } } else { diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index ac293990f..7d07860de 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -97,16 +97,10 @@ private: void set_mission_items(); /** - * Try to set the current position setpoint from an onboard mission item + * Try to set given mission item from an offboard/onboard mission item * @return true if mission item successfully set */ - bool is_current_onboard_mission_item_set(struct position_setpoint_s *current_pos_sp); - - /** - * Try to set the current position setpoint from an offboard mission item - * @return true if mission item successfully set - */ - bool is_current_offboard_mission_item_set(struct position_setpoint_s *current_pos_sp); + bool set_mission_item(bool onboard, bool next_item, struct mission_item_s *mission_item); /** * Try to set the next position setpoint from an onboard mission item diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index bf3c934a6..cbf7ac987 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -202,9 +202,10 @@ MissionBlock::mission_item_to_position_setpoint(const struct mission_item_s *ite } void -MissionBlock::set_previous_pos_setpoint(struct position_setpoint_triplet_s *pos_sp_triplet) +MissionBlock::set_previous_pos_setpoint() { - /* reuse current setpoint as previous setpoint */ + struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); + if (pos_sp_triplet->current.valid) { memcpy(&pos_sp_triplet->previous, &pos_sp_triplet->current, sizeof(struct position_setpoint_s)); } diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h index 22f42cc31..adf50bc39 100644 --- a/src/modules/navigator/mission_block.h +++ b/src/modules/navigator/mission_block.h @@ -86,7 +86,7 @@ protected: /** * Set previous position setpoint to current setpoint */ - void set_previous_pos_setpoint(struct position_setpoint_triplet_s *pos_sp_triplet); + void set_previous_pos_setpoint(); /** * Set a loiter mission item, if possible reuse the position setpoint, otherwise take the current position diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp index 7cf6bb1a8..6d7afcf4b 100644 --- a/src/modules/navigator/rtl.cpp +++ b/src/modules/navigator/rtl.cpp @@ -82,7 +82,7 @@ RTL::on_inactive() } void -RTL::on_activation(struct position_setpoint_triplet_s *pos_sp_triplet) +RTL::on_activation() { /* decide where to enter the RTL procedure when we switch into it */ if (_rtl_state == RTL_STATE_NONE) { @@ -105,28 +105,27 @@ RTL::on_activation(struct position_setpoint_triplet_s *pos_sp_triplet) } } - set_rtl_item(pos_sp_triplet); + set_rtl_item(); } -bool -RTL::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) +void +RTL::on_active() { if (_rtl_state != RTL_STATE_LANDED && is_mission_item_reached()) { advance_rtl(); - set_rtl_item(pos_sp_triplet); - return true; + set_rtl_item(); } - - return false; } void -RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet) +RTL::set_rtl_item() { + struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); + /* make sure we have the latest params */ updateParams(); - set_previous_pos_setpoint(pos_sp_triplet); + set_previous_pos_setpoint(); _navigator->set_can_loiter_at_sp(false); switch (_rtl_state) { @@ -273,11 +272,13 @@ RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet) break; } + reset_mission_item_reached(); + /* convert mission item to current position setpoint and make it valid */ mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); - reset_mission_item_reached(); - pos_sp_triplet->current.valid = true; pos_sp_triplet->next.valid = false; + + _navigator->set_position_setpoint_triplet_updated(); } void diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h index 9c8b3fdfc..5928f1f07 100644 --- a/src/modules/navigator/rtl.h +++ b/src/modules/navigator/rtl.h @@ -63,15 +63,15 @@ public: virtual void on_inactive(); - virtual void on_activation(position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_activation(); - virtual bool on_active(position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_active(); private: /** * Set the RTL item */ - void set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet); + void set_rtl_item(); /** * Move to next RTL item -- cgit v1.2.3 From 72071cdcd39cae6be8533e67d01cbc7533ca6cb1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 29 Jun 2014 19:22:22 +0200 Subject: Fix failed merge --- src/modules/mavlink/mavlink_main.h | 54 -------------------------------------- 1 file changed, 54 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 18141972a..91d79057c 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -138,14 +138,6 @@ public: bool get_forwarding_on() { return _forwarding_on; } -<<<<<<< HEAD -======= - /** - * Handle waypoint related messages. - */ - void mavlink_wpm_message_handler(const mavlink_message_t *msg); ->>>>>>> 94c69e11ae1ec44c80eec1c979201c7d7e51cdb0 - static int start_helper(int argc, char *argv[]); /** @@ -165,15 +157,11 @@ public: */ int set_hil_enabled(bool hil_enabled); -<<<<<<< HEAD void send_message(const mavlink_message_t *msg); void handle_message(const mavlink_message_t *msg); MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic); -======= - MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic); ->>>>>>> 94c69e11ae1ec44c80eec1c979201c7d7e51cdb0 int get_instance_id(); @@ -228,7 +216,6 @@ private: MavlinkOrbSubscription *_subscriptions; MavlinkStream *_streams; -<<<<<<< HEAD MavlinkMissionManager *_mission_manager; orb_advert_t _mission_pub; @@ -236,32 +223,12 @@ private: MAVLINK_MODE _mode; mavlink_channel_t _channel; -======= - orb_advert_t _mission_pub; - struct mission_s mission; - MAVLINK_MODE _mode; - - uint8_t _mavlink_wpm_comp_id; - mavlink_channel_t _channel; ->>>>>>> 94c69e11ae1ec44c80eec1c979201c7d7e51cdb0 struct mavlink_logbuffer _logbuffer; unsigned int _total_counter; pthread_t _receive_thread; -<<<<<<< HEAD - bool _verbose; - bool _forwarding_on; - bool _passing_on; - int _uart_fd; - int _baudrate; - int _datarate; -======= - /* Allocate storage space for waypoints */ - mavlink_wpm_storage _wpm_s; - mavlink_wpm_storage *_wpm; - bool _verbose; bool _forwarding_on; bool _passing_on; @@ -269,7 +236,6 @@ private: int _uart_fd; int _baudrate; int _datarate; ->>>>>>> 94c69e11ae1ec44c80eec1c979201c7d7e51cdb0 /** * If the queue index is not at 0, the queue sending @@ -347,26 +313,9 @@ private: void mavlink_update_system(); -<<<<<<< HEAD uint8_t get_system_id(); uint8_t get_component_id(); -======= - void mavlink_waypoint_eventloop(uint64_t now); - void mavlink_wpm_send_waypoint_reached(uint16_t seq); - void mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, uint16_t seq); - void mavlink_wpm_send_waypoint(uint8_t sysid, uint8_t compid, uint16_t seq); - void mavlink_wpm_send_waypoint_count(uint8_t sysid, uint8_t compid, uint16_t count); - void mavlink_wpm_send_waypoint_current(uint16_t seq); - void mavlink_wpm_send_waypoint_ack(uint8_t sysid, uint8_t compid, uint8_t type); - void mavlink_wpm_init(mavlink_wpm_storage *state); - int map_mission_item_to_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item); - int map_mavlink_mission_item_to_mission_item(const mavlink_mission_item_t *mavlink_mission_item, struct mission_item_s *mission_item); - void publish_mission(); - - void mavlink_missionlib_send_message(mavlink_message_t *msg); - int mavlink_missionlib_send_gcs_string(const char *string); ->>>>>>> 94c69e11ae1ec44c80eec1c979201c7d7e51cdb0 int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb); @@ -381,11 +330,8 @@ private: int message_buffer_is_empty(); -<<<<<<< HEAD bool message_buffer_write(const void *ptr, int size); -======= ->>>>>>> 94c69e11ae1ec44c80eec1c979201c7d7e51cdb0 int message_buffer_get_ptr(void **ptr, bool *is_part); void message_buffer_mark_read(int n); -- cgit v1.2.3 From 43b9d96cf4306bc472d16956f5437dbef7c630c0 Mon Sep 17 00:00:00 2001 From: Kynos Date: Mon, 30 Jun 2014 01:55:40 +0200 Subject: Merged upstream master, add missing change --- src/modules/mavlink/mavlink_messages.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 472e2810d..06c2e737e 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -669,16 +669,16 @@ protected: if (gps_sub->update(&gps_time, &gps)) { mavlink_msg_gps_raw_int_send(_channel, - gps->timestamp_position, - gps->fix_type, - gps->lat, - gps->lon, - gps->alt, - cm_uint16_from_m_float(gps->eph), - cm_uint16_from_m_float(gps->epv), - gps->vel_m_s * 100.0f, - _wrap_2pi(gps->cog_rad) * M_RAD_TO_DEG_F * 1e2f, - gps->satellites_used); + gps.timestamp_position, + gps.fix_type, + gps.lat, + gps.lon, + gps.alt, + cm_uint16_from_m_float(gps.eph), + cm_uint16_from_m_float(gps.epv), + gps.vel_m_s * 100.0f, + _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f, + gps.satellites_used); } } }; -- cgit v1.2.3 From e8c34fa174c6a47d5d2def2417c58beb846bb30f Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 30 Jun 2014 10:25:57 +0200 Subject: force setpoint uorb topic: add yaw field --- src/modules/uORB/topics/vehicle_force_setpoint.h | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/uORB/topics/vehicle_force_setpoint.h b/src/modules/uORB/topics/vehicle_force_setpoint.h index cd948985f..e3a7360b2 100644 --- a/src/modules/uORB/topics/vehicle_force_setpoint.h +++ b/src/modules/uORB/topics/vehicle_force_setpoint.h @@ -52,6 +52,7 @@ struct vehicle_force_setpoint_s { float x; /**< in N NED */ float y; /**< in N NED */ float z; /**< in N NED */ + float yaw; /**< right-hand rotation around downward axis (rad, equivalent to Tait-Bryan yaw) */ }; /**< Desired force in NED frame */ /** -- cgit v1.2.3 From a4315aee2ee69068c9a13568091805e20d0b04c5 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 30 Jun 2014 10:47:08 +0200 Subject: navigator: mission mode fixed --- src/modules/navigator/mission.cpp | 63 ++++++++++++++++----------------------- src/modules/navigator/mission.h | 21 ++----------- 2 files changed, 27 insertions(+), 57 deletions(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index fbfd1259d..f207776a9 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -70,9 +70,9 @@ Mission::Mission(Navigator *navigator, const char *name) : { /* load initial params */ updateParams(); + /* set initial mission items */ on_inactive(); - } Mission::~Mission() @@ -121,16 +121,12 @@ Mission::on_active() /* reset mission items if needed */ if (onboard_updated || offboard_updated) { set_mission_items(); - - _navigator->set_position_setpoint_triplet_updated(); } /* lets check if we reached the current mission item */ if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) { advance_mission(); set_mission_items(); - - _navigator->set_position_setpoint_triplet_updated(); } } @@ -223,13 +219,16 @@ Mission::advance_mission() void Mission::set_mission_items() { + /* make sure param is up to date */ + updateParams(); + struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); /* set previous position setpoint to current */ set_previous_pos_setpoint(); /* try setting onboard mission item */ - if (set_mission_item(true, false, &_mission_item)) { + if (_param_onboard_enabled.get() && read_mission_item(true, true, &_mission_item)) { /* if mission type changed, notify */ if (_mission_type != MISSION_TYPE_ONBOARD) { mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: onboard mission running"); @@ -237,7 +236,7 @@ Mission::set_mission_items() _mission_type = MISSION_TYPE_ONBOARD; /* try setting offboard mission item */ - } else if (set_mission_item(false, false, &_mission_item)) { + } else if (read_mission_item(false, true, &_mission_item)) { /* if mission type changed, notify */ if (_mission_type != MISSION_TYPE_OFFBOARD) { mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: offboard mission running"); @@ -284,7 +283,8 @@ Mission::set_mission_items() /* try to read next mission item */ struct mission_item_s mission_item_next; - if (!set_mission_item(_mission_type == MISSION_TYPE_ONBOARD, true, &mission_item_next)) { + + if (read_mission_item(_mission_type == MISSION_TYPE_ONBOARD, false, &mission_item_next)) { /* got next mission item, update setpoint triplet */ mission_item_to_position_setpoint(&mission_item_next, &pos_sp_triplet->next); @@ -297,11 +297,8 @@ Mission::set_mission_items() } bool -Mission::set_mission_item(bool onboard, bool next_item, struct mission_item_s *mission_item) +Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s *mission_item) { - /* make sure param is up to date */ - updateParams(); - /* select onboard/offboard mission */ int *mission_index_ptr; struct mission_s *mission; @@ -310,12 +307,8 @@ Mission::set_mission_item(bool onboard, bool next_item, struct mission_item_s *m if (onboard) { /* onboard mission */ - if (!_param_onboard_enabled.get()) { - return false; - } - mission_index_next = _current_onboard_mission_index + 1; - mission_index_ptr = next_item ? &mission_index_next : &_current_onboard_mission_index; + mission_index_ptr = is_current ? &_current_onboard_mission_index : &mission_index_next; mission = &_onboard_mission; @@ -324,7 +317,7 @@ Mission::set_mission_item(bool onboard, bool next_item, struct mission_item_s *m } else { /* offboard mission */ mission_index_next = _current_offboard_mission_index + 1; - mission_index_ptr = next_item ? &mission_index_next : &_current_offboard_mission_index; + mission_index_ptr = is_current ? &_current_offboard_mission_index : &mission_index_next; mission = &_offboard_mission; @@ -336,27 +329,20 @@ Mission::set_mission_item(bool onboard, bool next_item, struct mission_item_s *m } } - if (*mission_index_ptr >= 0 && *mission_index_ptr < (int)mission->count) { - struct mission_item_s new_mission_item; - - if (read_mission_item(dm_item, true, mission_index_ptr, &new_mission_item)) { - memcpy(&mission_item, &new_mission_item, sizeof(struct mission_item_s)); - return true; - } + if (*mission_index_ptr < 0 || *mission_index_ptr >= (int)mission->count) { + /* mission item index out of bounds */ + return false; } - return false; -} -bool -Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index_ptr, - struct mission_item_s *new_mission_item) -{ /* repeat several to get the mission item because we might have to follow multiple DO_JUMPS */ for (int i = 0; i < 10; i++) { const ssize_t len = sizeof(struct mission_item_s); + /* read mission item to temp storage first to not overwrite current mission item if data damaged */ + struct mission_item_s mission_item_tmp; + /* read mission item from datamanager */ - if (dm_read(dm_item, *mission_index_ptr, new_mission_item, len) != len) { + if (dm_read(dm_item, *mission_index_ptr, &mission_item_tmp, len) != len) { /* not supposed to happen unless the datamanager can't access the SD card, etc. */ mavlink_log_critical(_navigator->get_mavlink_fd(), "#audio: ERROR waypoint could not be read"); @@ -364,18 +350,17 @@ Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *missio } /* check for DO_JUMP item, and whether it hasn't not already been repeated enough times */ - if (new_mission_item->nav_cmd == NAV_CMD_DO_JUMP) { + if (mission_item_tmp.nav_cmd == NAV_CMD_DO_JUMP) { /* do DO_JUMP as many times as requested */ - if (new_mission_item->do_jump_current_count < new_mission_item->do_jump_repeat_count) { + if (mission_item_tmp.do_jump_current_count < mission_item_tmp.do_jump_repeat_count) { /* only raise the repeat count if this is for the current mission item * but not for the next mission item */ if (is_current) { - (new_mission_item->do_jump_current_count)++; + (mission_item_tmp.do_jump_current_count)++; /* save repeat count */ - if (dm_write(dm_item, *mission_index_ptr, DM_PERSIST_IN_FLIGHT_RESET, - new_mission_item, len) != len) { + if (dm_write(dm_item, *mission_index_ptr, DM_PERSIST_IN_FLIGHT_RESET, &mission_item_tmp, len) != len) { /* not supposed to happen unless the datamanager can't access the * dataman */ mavlink_log_critical(_navigator->get_mavlink_fd(), @@ -385,7 +370,8 @@ Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *missio } /* set new mission item index and repeat * we don't have to validate here, if it's invalid, we should realize this later .*/ - *mission_index_ptr = new_mission_item->do_jump_mission_index; + *mission_index_ptr = mission_item_tmp.do_jump_mission_index; + } else { mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: DO JUMP repetitions completed"); @@ -395,6 +381,7 @@ Mission::read_mission_item(const dm_item_t dm_item, bool is_current, int *missio } else { /* if it's not a DO_JUMP, then we were successful */ + memcpy(mission_item, &mission_item_tmp, sizeof(struct mission_item_s)); return true; } } diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index 7d07860de..29e4d41f6 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -97,27 +97,10 @@ private: void set_mission_items(); /** - * Try to set given mission item from an offboard/onboard mission item - * @return true if mission item successfully set - */ - bool set_mission_item(bool onboard, bool next_item, struct mission_item_s *mission_item); - - /** - * Try to set the next position setpoint from an onboard mission item - */ - void get_next_onboard_mission_item(struct position_setpoint_s *next_pos_sp); - - /** - * Try to set the next position setpoint from an offboard mission item - */ - void get_next_offboard_mission_item(struct position_setpoint_s *next_pos_sp); - - /** - * Read a mission item from the dataman and watch out for DO_JUMPS + * Read current or next mission item from the dataman and watch out for DO_JUMPS * @return true if successful */ - bool read_mission_item(const dm_item_t dm_item, bool is_current, int *mission_index, - struct mission_item_s *new_mission_item); + bool read_mission_item(bool onboard, bool is_current, struct mission_item_s *mission_item); /** * Report that a mission item has been reached -- cgit v1.2.3 From 59775efaad782a1e4f5e346832407c71f1355c89 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 30 Jun 2014 12:02:29 +0200 Subject: navigator: takeoff on start of mission implemented --- src/modules/navigator/mission.cpp | 133 ++++++++++++++++++++++++++++++-------- src/modules/navigator/mission.h | 3 + 2 files changed, 109 insertions(+), 27 deletions(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index f207776a9..2e5047e2c 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -60,13 +60,16 @@ Mission::Mission(Navigator *navigator, const char *name) : MissionBlock(navigator, name), _param_onboard_enabled(this, "ONBOARD_EN"), + _param_takeoff_alt(this, "TAKEOFF_ALT"), _onboard_mission({0}), _offboard_mission({0}), _current_onboard_mission_index(-1), _current_offboard_mission_index(-1), _mission_result_pub(-1), _mission_result({0}), - _mission_type(MISSION_TYPE_NONE) + _mission_type(MISSION_TYPE_NONE), + _need_takeoff(true), + _takeoff(false) { /* load initial params */ updateParams(); @@ -94,6 +97,10 @@ Mission::on_inactive() if (offboard_updated) { update_offboard_mission(); } + + if (!_navigator->get_can_loiter_at_sp() || _navigator->get_vstatus()->condition_landed) { + _need_takeoff = true; + } } void @@ -127,6 +134,12 @@ Mission::on_active() if (_mission_type != MISSION_TYPE_NONE && is_mission_item_reached()) { advance_mission(); set_mission_items(); + + } else { + /* if waypoint position reached allow loiter on the setpoint */ + if (_waypoint_position_reached && _mission_item.nav_cmd != NAV_CMD_IDLE) { + _navigator->set_can_loiter_at_sp(true); + } } } @@ -148,6 +161,7 @@ Mission::update_onboard_mission() } /* otherwise, just leave it */ } + } else { _onboard_mission.count = 0; _onboard_mission.current_index = 0; @@ -164,10 +178,12 @@ Mission::update_offboard_mission() if (_offboard_mission.current_index >= 0 && _offboard_mission.current_index < (int)_offboard_mission.count) { _current_offboard_mission_index = _offboard_mission.current_index; + } else { /* if less WPs available, reset to first WP */ if (_current_offboard_mission_index >= (int)_offboard_mission.count) { _current_offboard_mission_index = 0; + /* if not initialized, set it to 0 */ } else if (_current_offboard_mission_index < 0) { _current_offboard_mission_index = 0; @@ -181,6 +197,7 @@ Mission::update_offboard_mission() if (_offboard_mission.dataman_id == 0) { dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0; + } else { dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1; } @@ -189,11 +206,13 @@ Mission::update_offboard_mission() (size_t)_offboard_mission.count, _navigator->get_geofence(), _navigator->get_home_position()->alt); + } else { _offboard_mission.count = 0; _offboard_mission.current_index = 0; _current_offboard_mission_index = 0; } + report_current_offboard_mission_item(); } @@ -201,18 +220,23 @@ Mission::update_offboard_mission() void Mission::advance_mission() { - switch (_mission_type) { - case MISSION_TYPE_ONBOARD: - _current_onboard_mission_index++; - break; - - case MISSION_TYPE_OFFBOARD: - _current_offboard_mission_index++; - break; - - case MISSION_TYPE_NONE: - default: - break; + if (_takeoff) { + _takeoff = false; + + } else { + switch (_mission_type) { + case MISSION_TYPE_ONBOARD: + _current_onboard_mission_index++; + break; + + case MISSION_TYPE_OFFBOARD: + _current_offboard_mission_index++; + break; + + case MISSION_TYPE_NONE: + default: + break; + } } } @@ -271,26 +295,81 @@ Mission::set_mission_items() return; } - /* new current mission item set */ - mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); - _navigator->set_can_loiter_at_sp(false); - reset_mission_item_reached(); + /* do takeoff on first waypoint for rotary wing vehicles */ + if (_navigator->get_vstatus()->is_rotary_wing) { + /* force takeoff if landed (additional protection) */ + if (!_takeoff && _navigator->get_vstatus()->condition_landed) { + _need_takeoff = true; + } - if (_mission_type == MISSION_TYPE_OFFBOARD) { - report_current_offboard_mission_item(); + /* new current mission item set, check if we need takeoff */ + if (_need_takeoff && ( + _mission_item.nav_cmd == NAV_CMD_TAKEOFF || + _mission_item.nav_cmd == NAV_CMD_WAYPOINT || + _mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT || + _mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT || + _mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED || + _mission_item.nav_cmd == NAV_CMD_RETURN_TO_LAUNCH)) { + _takeoff = true; + _need_takeoff = false; + } } - // TODO: report onboard mission item somehow - /* try to read next mission item */ - struct mission_item_s mission_item_next; + if (_takeoff) { + /* do takeoff before going to setpoint */ + /* set mission item as next position setpoint */ + mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->next); - if (read_mission_item(_mission_type == MISSION_TYPE_ONBOARD, false, &mission_item_next)) { - /* got next mission item, update setpoint triplet */ - mission_item_to_position_setpoint(&mission_item_next, &pos_sp_triplet->next); + /* calculate takeoff altitude */ + float takeoff_alt = _mission_item.altitude; + if (_mission_item.altitude_is_relative) { + takeoff_alt += _navigator->get_home_position()->alt; + } + + if (_navigator->get_vstatus()->condition_landed) { + takeoff_alt = fmaxf(takeoff_alt, _navigator->get_global_position()->alt + _param_takeoff_alt.get()); + + } else { + takeoff_alt = _navigator->get_home_position()->alt + _param_takeoff_alt.get(); + } + + mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: takeoff to %.1fm above home", takeoff_alt - _navigator->get_home_position()->alt); + + _mission_item.lat = _navigator->get_global_position()->lat; + _mission_item.lon = _navigator->get_global_position()->lon; + _mission_item.altitude = takeoff_alt; + _mission_item.altitude_is_relative = false; + + mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); } else { - /* next mission item is not available */ - pos_sp_triplet->next.valid = false; + /* set current position setpoint from mission item */ + mission_item_to_position_setpoint(&_mission_item, &pos_sp_triplet->current); + + /* require takeoff after landing or idle */ + if (pos_sp_triplet->current.type == SETPOINT_TYPE_LAND || pos_sp_triplet->current.type == SETPOINT_TYPE_IDLE) { + _need_takeoff = true; + } + + _navigator->set_can_loiter_at_sp(false); + reset_mission_item_reached(); + + if (_mission_type == MISSION_TYPE_OFFBOARD) { + report_current_offboard_mission_item(); + } + // TODO: report onboard mission item somehow + + /* try to read next mission item */ + struct mission_item_s mission_item_next; + + if (read_mission_item(_mission_type == MISSION_TYPE_ONBOARD, false, &mission_item_next)) { + /* got next mission item, update setpoint triplet */ + mission_item_to_position_setpoint(&mission_item_next, &pos_sp_triplet->next); + + } else { + /* next mission item is not available */ + pos_sp_triplet->next.valid = false; + } } _navigator->set_position_setpoint_triplet_updated(); diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index 29e4d41f6..d4808b6f4 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -123,12 +123,15 @@ private: void publish_mission_result(); control::BlockParamFloat _param_onboard_enabled; + control::BlockParamFloat _param_takeoff_alt; struct mission_s _onboard_mission; struct mission_s _offboard_mission; int _current_onboard_mission_index; int _current_offboard_mission_index; + bool _need_takeoff; + bool _takeoff; orb_advert_t _mission_result_pub; struct mission_result_s _mission_result; -- cgit v1.2.3 From 0a159e1a2490e5ec7f368d938e2b0fd365d2731e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 30 Jun 2014 12:31:29 +0200 Subject: mavlink, commander: bugs fixed --- src/modules/commander/commander.cpp | 2 +- src/modules/mavlink/mavlink_main.h | 10 ++-------- 2 files changed, 3 insertions(+), 9 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 0ff1195c9..bba14ea27 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1407,7 +1407,7 @@ int commander_thread_main(int argc, char *argv[]) /* now set navigation state according to failsafe and main state */ bool nav_state_changed = set_nav_state(&status, (bool)datalink_loss_enabled, - mission_result.mission_finished); + mission_result.finished); // TODO handle mode changes by commands if (main_state_changed) { diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index b4184b21c..67ef8d00f 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -182,7 +182,7 @@ public: int send_statustext(const char *string); int send_statustext(enum MAV_SEVERITY severity, const char *string); - MavlinkStream * get_streams() { return _streams; } const + MavlinkStream * get_streams() const { return _streams; } float get_rate_mult(); @@ -193,7 +193,7 @@ public: bool get_wait_to_transmit() { return _wait_to_transmit; } bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); } - bool message_buffer_write(void *ptr, int size); + bool message_buffer_write(const void *ptr, int size); void lockMessageBufferMutex(void) { pthread_mutex_lock(&_message_buffer_mutex); } void unlockMessageBufferMutex(void) { pthread_mutex_unlock(&_message_buffer_mutex); } @@ -322,10 +322,6 @@ private: void mavlink_update_system(); - uint8_t get_system_id(); - - uint8_t get_component_id(); - int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb); int configure_stream(const char *stream_name, const float rate); @@ -338,8 +334,6 @@ private: int message_buffer_is_empty(); - bool message_buffer_write(const void *ptr, int size); - int message_buffer_get_ptr(void **ptr, bool *is_part); void message_buffer_mark_read(int n); -- cgit v1.2.3 From a1655bb8c4a7f2201887a52de60a519c029a7505 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 30 Jun 2014 12:42:26 +0200 Subject: rcS: start dataman before commander --- ROMFS/px4fmu_common/init.d/rcS | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 983a6a38f..b4e90c960 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -275,6 +275,11 @@ then # Try to get an USB console nshterm /dev/ttyACM0 & + # + # Start the datamanager + # + dataman start + # # Start the Commander (needs to be this early for in-air-restarts) # @@ -402,11 +407,6 @@ then fi fi - # - # Start the datamanager - # - dataman start - # # MAVLink # -- cgit v1.2.3 From f0cfa04b852212cd0be4bc1bffbc4eece54ce659 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 30 Jun 2014 20:55:02 +0200 Subject: mtecs blocks: fix warning --- src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h b/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h index e4e405227..4f18d36e8 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h @@ -72,8 +72,8 @@ public: * @return: true if the limit is applied, false otherwise */ bool limit(float& value, float& difference) { - float minimum = isAngularLimit() ? getMin() * M_DEG_TO_RAD_F : getMin(); - float maximum = isAngularLimit() ? getMax() * M_DEG_TO_RAD_F : getMax(); + float minimum = getIsAngularLimit() ? getMin() * M_DEG_TO_RAD_F : getMin(); + float maximum = getIsAngularLimit() ? getMax() * M_DEG_TO_RAD_F : getMax(); if (value < minimum) { difference = value - minimum; value = minimum; @@ -86,7 +86,7 @@ public: return false; } //accessor: - bool isAngularLimit() {return _isAngularLimit ;} + bool getIsAngularLimit() {return _isAngularLimit ;} float getMin() { return _min.get(); } float getMax() { return _max.get(); } void setMin(float value) { _min.set(value); } -- cgit v1.2.3 From 57827563b9b3b8771be28d580842d4fbcf084918 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 30 Jun 2014 21:11:05 +0200 Subject: fw pos ctrl l1 main: fix warning --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 38 ++++++++++------------ 1 file changed, 18 insertions(+), 20 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 000c02e3d..e877f0e84 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -414,11 +414,23 @@ FixedwingPositionControl::FixedwingPositionControl() : _attitude_sp_pub(-1), _nav_capabilities_pub(-1), +/* states */ + _att(), + _att_sp(), + _nav_capabilities(), + _manual(), + _airspeed(), + _control_mode(), + _global_pos(), + _pos_sp_triplet(), + _sensor_combined(), + _range_finder(), + /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")), -/* states */ _loiter_hold(false), + _launch_valid(false), land_noreturn_horizontal(false), land_noreturn_vertical(false), land_stayonground(false), @@ -427,24 +439,17 @@ FixedwingPositionControl::FixedwingPositionControl() : launch_detected(false), usePreTakeoffThrust(false), last_manual(false), + landingslope(), flare_curve_alt_rel_last(0.0f), launchDetector(), _airspeed_error(0.0f), _airspeed_valid(false), + _airspeed_last_valid(0), _groundspeed_undershoot(0.0f), _global_pos_valid(false), - _att(), - _att_sp(), - _nav_capabilities(), - _manual(), - _airspeed(), - _control_mode(), - _global_pos(), - _pos_sp_triplet(), - _sensor_combined(), + _l1_control(), _mTecs(), - _was_pos_control_mode(false), - _range_finder() + _was_pos_control_mode(false) { _nav_capabilities.turn_distance = 0.0f; @@ -806,13 +811,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float eas2tas = 1.0f; // XXX calculate actual number based on current measurements - // XXX re-visit - float baro_altitude = _global_pos.alt; - - /* filter speed and altitude for controller */ - math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2); - math::Vector<3> accel_earth = _R_nb * accel_body; - + /* define altitude error */ float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt; /* no throttle limit as default */ @@ -945,7 +944,6 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float airspeed_approach = 1.3f * _parameters.airspeed_min; /* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */ - float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)); float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.alt : 0.0f; float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1)); -- cgit v1.2.3 From 02db53cea57d1e2c643b6efc1c357afa3e6be20e Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 30 Jun 2014 21:13:29 +0200 Subject: fw pos ctrl l1 main: initialize all subscriptions --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index e877f0e84..5ec49b6f8 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -129,7 +129,6 @@ private: int _global_pos_sub; int _pos_sp_triplet_sub; int _att_sub; /**< vehicle attitude subscription */ - int _attitude_sub; /**< raw rc channels data subscription */ int _airspeed_sub; /**< airspeed subscription */ int _control_mode_sub; /**< vehicle status subscription */ int _params_sub; /**< notification of parameter updates */ @@ -408,6 +407,7 @@ FixedwingPositionControl::FixedwingPositionControl() : _control_mode_sub(-1), _params_sub(-1), _manual_control_sub(-1), + _sensor_combined_sub(-1), _range_finder_sub(-1), /* publications */ -- cgit v1.2.3 From 173da25c9a55185377870f703cd751fd44b902f0 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 30 Jun 2014 21:16:32 +0200 Subject: fw pos ctrl l1 main: remove unused modes --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 83 ---------------------- 1 file changed, 83 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 5ec49b6f8..fc0d588d2 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -1133,89 +1133,6 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi _att_sp.roll_reset_integral = true; } - } else if (0/* posctrl mode enabled */) { - - _was_pos_control_mode = false; - - /** POSCTRL FLIGHT **/ - - if (0/* switched from another mode to posctrl */) { - _altctrl_hold_heading = _att.yaw; - } - - if (0/* posctrl on and manual control yaw non-zero */) { - _altctrl_hold_heading = _att.yaw + _manual.r; - } - - //XXX not used - - /* climb out control */ -// bool climb_out = false; -// -// /* user wants to climb out */ -// if (_manual.pitch > 0.3f && _manual.throttle > 0.8f) { -// climb_out = true; -// } - - /* if in altctrl mode, set airspeed based on manual control */ - - // XXX check if ground speed undershoot should be applied here - float altctrl_airspeed = _parameters.airspeed_min + - (_parameters.airspeed_max - _parameters.airspeed_min) * - _manual.z; - - _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed_2d); - _att_sp.roll_body = _l1_control.nav_roll(); - _att_sp.yaw_body = _l1_control.nav_bearing(); - - tecs_update_pitch_throttle(_global_pos.alt + _manual.x * 2.0f, altctrl_airspeed, eas2tas, - math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max), - _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise, - false, math::radians(_parameters.pitch_limit_min), _global_pos.alt, ground_speed); - - } else if (0/* altctrl mode enabled */) { - - _was_pos_control_mode = false; - - /** ALTCTRL FLIGHT **/ - - if (0/* switched from another mode to altctrl */) { - _altctrl_hold_heading = _att.yaw; - } - - if (0/* altctrl on and manual control yaw non-zero */) { - _altctrl_hold_heading = _att.yaw + _manual.r; - } - - /* if in altctrl mode, set airspeed based on manual control */ - - // XXX check if ground speed undershoot should be applied here - float altctrl_airspeed = _parameters.airspeed_min + - (_parameters.airspeed_max - _parameters.airspeed_min) * - _manual.z; - - /* user switched off throttle */ - if (_manual.z < 0.1f) { - throttle_max = 0.0f; - } - - /* climb out control */ - bool climb_out = false; - - /* user wants to climb out */ - if (_manual.x > 0.3f && _manual.z > 0.8f) { - climb_out = true; - } - - _l1_control.navigate_heading(_altctrl_hold_heading, _att.yaw, ground_speed_2d); - _att_sp.roll_body = _manual.y; - _att_sp.yaw_body = _manual.r; - tecs_update_pitch_throttle(_global_pos.alt + _manual.x * 2.0f, altctrl_airspeed, eas2tas, - math::radians(_parameters.pitch_limit_min), math::radians(_parameters.pitch_limit_max), - _parameters.throttle_min, _parameters.throttle_max, _parameters.throttle_cruise, - climb_out, math::radians(_parameters.pitch_limit_min), - _global_pos.alt, ground_speed); - } else { _was_pos_control_mode = false; -- cgit v1.2.3 From 62a92542891d32d88c1993e03da9a17d59f70d04 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 30 Jun 2014 21:22:56 +0200 Subject: fw pos ctrl l1 main: remove several unused vars --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 30 ---------------------- 1 file changed, 30 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index fc0d588d2..445abf23e 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -152,18 +152,6 @@ private: perf_counter_t _loop_perf; /**< loop performance counter */ - /** manual control states */ - float _altctrl_hold_heading; /**< heading the system should hold in altctrl mode */ - double _loiter_hold_lat; - double _loiter_hold_lon; - float _loiter_hold_alt; - bool _loiter_hold; - - double _launch_lat; - double _launch_lon; - float _launch_alt; - bool _launch_valid; - /* land states */ /* not in non-abort mode for landing yet */ bool land_noreturn_horizontal; @@ -429,8 +417,6 @@ FixedwingPositionControl::FixedwingPositionControl() : /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")), - _loiter_hold(false), - _launch_valid(false), land_noreturn_horizontal(false), land_noreturn_vertical(false), land_stayonground(false), @@ -609,13 +595,6 @@ FixedwingPositionControl::vehicle_control_mode_poll() bool was_armed = _control_mode.flag_armed; orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); - - if (!was_armed && _control_mode.flag_armed) { - _launch_lat = _global_pos.lat; - _launch_lon = _global_pos.lon; - _launch_alt = _global_pos.alt; - _launch_valid = true; - } } } @@ -1109,15 +1088,6 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi } } - // warnx("nav bearing: %8.4f bearing err: %8.4f target bearing: %8.4f", (double)_l1_control.nav_bearing(), - // (double)_l1_control.bearing_error(), (double)_l1_control.target_bearing()); - // warnx("prev wp: %8.4f/%8.4f, next wp: %8.4f/%8.4f prev:%s", (double)prev_wp(0), (double)prev_wp(1), - // (double)next_wp(0), (double)next_wp(1), (pos_sp_triplet.previous_valid) ? "valid" : "invalid"); - - // XXX at this point we always want no loiter hold if a - // mission is active - _loiter_hold = false; - /* reset landing state */ if (pos_sp_triplet.current.type != SETPOINT_TYPE_LAND) { reset_landing_state(); -- cgit v1.2.3 From 527ce1048a27f0d15e99a4ba899897c06a8cb3f2 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 30 Jun 2014 21:25:18 +0200 Subject: fw pos ctrl l1 main: init target_bearing --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 445abf23e..56fe65f9f 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -168,8 +168,8 @@ private: /* Landingslope object */ Landingslope landingslope; - float flare_curve_alt_rel_last; + /* heading hold */ float target_bearing; @@ -427,6 +427,7 @@ FixedwingPositionControl::FixedwingPositionControl() : last_manual(false), landingslope(), flare_curve_alt_rel_last(0.0f), + target_bearing(0.0f), launchDetector(), _airspeed_error(0.0f), _airspeed_valid(false), -- cgit v1.2.3 From c782d5d3796f9f936c30de2b0395ba76b42b8795 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 30 Jun 2014 21:27:05 +0200 Subject: fw pos ctrl l1 main: remove never used var --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 56fe65f9f..38d275eb0 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -593,8 +593,6 @@ FixedwingPositionControl::vehicle_control_mode_poll() if (vstatus_updated) { - bool was_armed = _control_mode.flag_armed; - orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); } } -- cgit v1.2.3 From acca14673c4934ea8cdca46286db6d769c4dca40 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 30 Jun 2014 21:31:50 +0200 Subject: fw pos ctrl l1 main: remove code with no effect --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 38d275eb0..d07258094 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -592,7 +592,6 @@ FixedwingPositionControl::vehicle_control_mode_poll() orb_check(_control_mode_sub, &vstatus_updated); if (vstatus_updated) { - orb_copy(ORB_ID(vehicle_control_mode), _control_mode_sub, &_control_mode); } } @@ -1217,14 +1216,6 @@ FixedwingPositionControl::task_main() _mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); } - static uint64_t last_run = 0; - float deltaT = (hrt_absolute_time() - last_run) / 1000000.0f; - last_run = hrt_absolute_time(); - - /* guard against too large deltaT's */ - if (deltaT > 1.0f) - deltaT = 0.01f; - /* load local copies */ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos); -- cgit v1.2.3 From 45433c3711dba5c972e02e8c9263853164670a86 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 1 Jul 2014 09:52:18 +0200 Subject: Hotfix: Fix use of circuit breaker param --- src/modules/systemlib/circuit_breaker.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/systemlib/circuit_breaker.c b/src/modules/systemlib/circuit_breaker.c index b59531d69..8f697749e 100644 --- a/src/modules/systemlib/circuit_breaker.c +++ b/src/modules/systemlib/circuit_breaker.c @@ -86,7 +86,7 @@ PARAM_DEFINE_INT32(CBRK_IO_SAFETY, 0); bool circuit_breaker_enabled(const char* breaker, int32_t magic) { int32_t val; - (void)param_get(param_find(breaker), val); + (void)param_get(param_find(breaker), &val); return (val == magic); } -- cgit v1.2.3 From fb98251e4d08d351c7ba404e3816958435c57515 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 1 Jul 2014 09:52:36 +0200 Subject: Warning fixes in commander --- src/modules/commander/state_machine_helper.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 244513375..423ce2f23 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -182,7 +182,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current if (status->condition_power_input_valid && (status->avionics_power_rail_voltage > 0.0f) && (status->avionics_power_rail_voltage < 4.9f)) { - mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Avionics power low: %6.2f V.", status->avionics_power_rail_voltage); + mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage); valid_transition = false; } } @@ -638,7 +638,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) } if (!status->is_rotary_wing) { - int fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); + fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); if (fd < 0) { mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED SENSOR MISSING"); -- cgit v1.2.3 From 534c377ec6d09aff0feed9eb7e70c9188abcda8c Mon Sep 17 00:00:00 2001 From: philipoe Date: Tue, 1 Jul 2014 10:49:59 +0200 Subject: TECS: Small fix to throttle feed-forward --- src/lib/external_lgpl/tecs/tecs.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp index 3730b1920..6386e37a0 100644 --- a/src/lib/external_lgpl/tecs/tecs.cpp +++ b/src/lib/external_lgpl/tecs/tecs.cpp @@ -310,7 +310,7 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM STEdot_dem = STEdot_dem + _rollComp * (1.0f / constrain(cosPhi , 0.1f, 1.0f) - 1.0f); if (STEdot_dem >= 0) { - ff_throttle = nomThr + STEdot_dem / _STEdot_max * (1.0f - nomThr); + ff_throttle = nomThr + STEdot_dem / _STEdot_max * (_THRmaxf - nomThr); } else { ff_throttle = nomThr - STEdot_dem / _STEdot_min * nomThr; -- cgit v1.2.3 From 15a7a0ce7fd01717e597a470b732d623c5fda5f6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 1 Jul 2014 11:31:24 +0200 Subject: autoconfig: Enforce clean defaults --- ROMFS/px4fmu_common/init.d/rcS | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index f70e0ed77..9a77da9f9 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -173,6 +173,10 @@ then # if [ $DO_AUTOCONFIG == yes ] then + # We can't be sure the defaults haven't changed, so + # if someone requests a re-configuration, we do it + # cleanly from scratch + param reset param set SYS_AUTOCONFIG 0 param save fi -- cgit v1.2.3 From 6042999aab26276ff87e7274b97b69200919b86f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 1 Jul 2014 11:59:25 +0200 Subject: Add vital comment to circuit breaker --- src/modules/systemlib/circuit_breaker.h | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/src/modules/systemlib/circuit_breaker.h b/src/modules/systemlib/circuit_breaker.h index 86439e2a5..1175dbce8 100644 --- a/src/modules/systemlib/circuit_breaker.h +++ b/src/modules/systemlib/circuit_breaker.h @@ -40,6 +40,15 @@ #ifndef CIRCUIT_BREAKER_H_ #define CIRCUIT_BREAKER_H_ +/* SAFETY WARNING -- SAFETY WARNING -- SAFETY WARNING + * + * OBEY THE DOCUMENTATION FOR ALL CIRCUIT BREAKERS HERE, + * ENSURE TO READ CAREFULLY ALL SAFETY WARNINGS. + * http://pixhawk.org/dev/circuit_breakers + * + * CIRCUIT BREAKERS ARE NOT PART OF THE STANDARD OPERATION PROCEDURE + * AND MAY DISABLE CHECKS THAT ARE VITAL FOR SAFE FLIGHT. + */ #define CBRK_SUPPLY_CHK_KEY 894281 #define CBRK_RATE_CTRL_KEY 140253 #define CBRK_IO_SAFETY_KEY 22027 -- cgit v1.2.3 From 29cd95ebad11380026c58343deeaf5bf334ad01c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 1 Jul 2014 12:05:10 +0200 Subject: Move param reset to right autoconfig check --- ROMFS/px4fmu_common/init.d/rcS | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 9a77da9f9..5856ba84f 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -132,6 +132,10 @@ then # if param compare SYS_AUTOCONFIG 1 then + # We can't be sure the defaults haven't changed, so + # if someone requests a re-configuration, we do it + # cleanly from scratch + param reset set DO_AUTOCONFIG yes else set DO_AUTOCONFIG no @@ -173,10 +177,6 @@ then # if [ $DO_AUTOCONFIG == yes ] then - # We can't be sure the defaults haven't changed, so - # if someone requests a re-configuration, we do it - # cleanly from scratch - param reset param set SYS_AUTOCONFIG 0 param save fi -- cgit v1.2.3 From d0b78aa8a09cd4259258ab10b77c98e907c3b460 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 1 Jul 2014 13:42:32 +0200 Subject: Add param command which does not reset the autostart params to not hamper auto-config --- ROMFS/px4fmu_common/init.d/rcS | 4 ++-- src/systemcmds/param/param.c | 28 ++++++++++++++++++++++++++++ 2 files changed, 30 insertions(+), 2 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 5856ba84f..1c9ded6a8 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -134,8 +134,8 @@ then then # We can't be sure the defaults haven't changed, so # if someone requests a re-configuration, we do it - # cleanly from scratch - param reset + # cleanly from scratch (except autostart / autoconfig) + param reset_nostart set DO_AUTOCONFIG yes else set DO_AUTOCONFIG no diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c index 328205e29..f8bff2f6f 100644 --- a/src/systemcmds/param/param.c +++ b/src/systemcmds/param/param.c @@ -64,6 +64,7 @@ static void do_show_print(void *arg, param_t param); static void do_set(const char* name, const char* val, bool fail_on_not_found); static void do_compare(const char* name, const char* vals[], unsigned comparisons); static void do_reset(void); +static void do_reset_nostart(void); int param_main(int argc, char *argv[]) @@ -142,6 +143,10 @@ param_main(int argc, char *argv[]) if (!strcmp(argv[1], "reset")) { do_reset(); } + + if (!strcmp(argv[1], "reset_nostart")) { + do_reset_nostart(); + } } errx(1, "expected a command, try 'load', 'import', 'show', 'set', 'compare', 'select' or 'save'"); @@ -427,3 +432,26 @@ do_reset(void) exit(0); } } + +static void +do_reset_nostart(void) +{ + + int32_t autostart; + int32_t autoconfig; + + (void)param_get(param_find("SYS_AUTOSTART"), &autostart); + (void)param_get(param_find("SYS_AUTOCONFIG"), &autoconfig); + + param_reset_all(); + + (void)param_set(param_find("SYS_AUTOSTART"), &autostart); + (void)param_set(param_find("SYS_AUTOCONFIG"), &autoconfig); + + if (param_save_default()) { + warnx("Param export failed."); + exit(1); + } else { + exit(0); + } +} -- cgit v1.2.3 From 8c638d2addad0831b71428591cd76629c436ee05 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 1 Jul 2014 14:28:48 +0200 Subject: XML tool --- Tools/px_generate_xml.sh | 2 ++ 1 file changed, 2 insertions(+) create mode 100644 Tools/px_generate_xml.sh diff --git a/Tools/px_generate_xml.sh b/Tools/px_generate_xml.sh new file mode 100644 index 000000000..65f0c95da --- /dev/null +++ b/Tools/px_generate_xml.sh @@ -0,0 +1,2 @@ +#!/bin/sh +python px_process_params.py --xml -- cgit v1.2.3 From 8acbe6d5b6770e92fdcb86ba268492217d3e26bd Mon Sep 17 00:00:00 2001 From: Andrew Chambers Date: Tue, 1 Jul 2014 14:08:59 -0700 Subject: Added class to convert gnss message from uavcan to uorb --- src/modules/uavcan/gnss_receiver.cpp | 122 +++++++++++++++++++++++++++++++++++ src/modules/uavcan/gnss_receiver.hpp | 86 ++++++++++++++++++++++++ src/modules/uavcan/uavcan_main.cpp | 7 +- src/modules/uavcan/uavcan_main.hpp | 2 + 4 files changed, 216 insertions(+), 1 deletion(-) create mode 100644 src/modules/uavcan/gnss_receiver.cpp create mode 100644 src/modules/uavcan/gnss_receiver.hpp diff --git a/src/modules/uavcan/gnss_receiver.cpp b/src/modules/uavcan/gnss_receiver.cpp new file mode 100644 index 000000000..e92468333 --- /dev/null +++ b/src/modules/uavcan/gnss_receiver.cpp @@ -0,0 +1,122 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file gnss_receiver.cpp + * + * @author Pavel Kirienko + * @author Andrew Chambers + * + */ + +#include "gnss_receiver.hpp" +#include + +#define MM_PER_CM 10 // Millimeters per centimeter + +UavcanGnssReceiver::UavcanGnssReceiver(uavcan::INode &node) : + _node(node), + _uavcan_sub_status(node), + _report_pub(-1) +{ +} + +int UavcanGnssReceiver::init() +{ + int res = -1; + + // GNSS fix subscription + res = _uavcan_sub_status.start(FixCbBinder(this, &UavcanGnssReceiver::gnss_fix_sub_cb)); + if (res < 0) + { + warnx("GNSS fix sub failed %i", res); + return res; + } + + // Clear the uORB GPS report + memset(&_report, 0, sizeof(_report)); + + return res; +} + +void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure &msg) +{ + _report.timestamp_position = hrt_absolute_time(); + _report.lat = msg.lat_1e7; + _report.lon = msg.lon_1e7; + _report.alt = msg.alt_1e2 * MM_PER_CM; // Convert from centimeter (1e2) to millimeters (1e3) + + _report.timestamp_variance = _report.timestamp_position; + _report.s_variance_m_s = msg.velocity_covariance[0] + msg.velocity_covariance[4] + msg.velocity_covariance[8]; + _report.p_variance_m = msg.position_covariance[0] + msg.position_covariance[4]; + + /* Use Jacobian to transform velocity covariance to heading covariance + * heading = atan2(vel_e_m_s, vel_n_m_s) + * For math, see http://en.wikipedia.org/wiki/Atan2#Derivative + * + * To calculate the variance of heading from the variance of velocity, + * var(heading) = J(velocity)*var(velocity)*J(velocity)^T + */ + _report.c_variance_rad = + msg.ned_velocity[1] * msg.ned_velocity[1] * msg.velocity_covariance[0] + + -2*msg.ned_velocity[1] * msg.ned_velocity[0] * msg.velocity_covariance[1] + + msg.ned_velocity[0] * msg.ned_velocity[0] * msg.velocity_covariance[4]; + + _report.fix_type = msg.status; + + _report.eph_m = sqrtf(_report.p_variance_m); + _report.epv_m = sqrtf(msg.position_covariance[8]); + + _report.timestamp_velocity = _report.timestamp_position; + _report.vel_n_m_s = msg.ned_velocity[0]; + _report.vel_e_m_s = msg.ned_velocity[1]; + _report.vel_d_m_s = msg.ned_velocity[2]; + _report.vel_m_s = sqrtf(_report.vel_n_m_s * _report.vel_n_m_s + _report.vel_e_m_s * _report.vel_e_m_s + _report.vel_d_m_s * _report.vel_d_m_s); + _report.cog_rad = atan2f(_report.vel_e_m_s, _report.vel_n_m_s); + _report.vel_ned_valid = true; + + _report.timestamp_time = _report.timestamp_position; + _report.time_gps_usec = msg.timestamp.husec * msg.timestamp.USEC_PER_LSB; // Convert to microseconds + + _report.timestamp_satellites = _report.timestamp_position; + _report.satellites_visible = msg.sats_used; + _report.satellite_info_available = 0; // Set to 0 for no info available + + if (_report_pub > 0) { + orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); + + } else { + _report_pub = orb_advertise(ORB_ID(vehicle_gps_position), &_report); + } + +} diff --git a/src/modules/uavcan/gnss_receiver.hpp b/src/modules/uavcan/gnss_receiver.hpp new file mode 100644 index 000000000..abb8a821a --- /dev/null +++ b/src/modules/uavcan/gnss_receiver.hpp @@ -0,0 +1,86 @@ +/**************************************************************************** + * + * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file gnss_receiver.hpp + * + * UAVCAN <--> ORB bridge for ESC messages: + * uavcan.equipment.esc.RawCommand + * uavcan.equipment.esc.RPMCommand + * uavcan.equipment.esc.Status + * + * @author Pavel Kirienko + * @author Andrew Chambers + */ + +#pragma once + +#include + +#include +#include + +#include +#include + +class UavcanGnssReceiver +{ +public: + UavcanGnssReceiver(uavcan::INode& node); + + int init(); + +private: + /** + * GNSS fix message will be reported via this callback. + */ + void gnss_fix_sub_cb(const uavcan::ReceivedDataStructure &msg); + + + typedef uavcan::MethodBinder&)> + FixCbBinder; + + /* + * libuavcan related things + */ + uavcan::INode &_node; + uavcan::Subscriber _uavcan_sub_status; + + /* + * uORB + */ + struct vehicle_gps_position_s _report; ///< uORB topic for gnss position + orb_advert_t _report_pub; ///< uORB pub for gnss position + +}; diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index ab687a6b9..5bc437670 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -63,7 +63,8 @@ UavcanNode *UavcanNode::_instance; UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) : CDev("uavcan", UAVCAN_DEVICE_PATH), _node(can_driver, system_clock), - _esc_controller(_node) + _esc_controller(_node), + _gnss_receiver(_node) { _control_topics[0] = ORB_ID(actuator_controls_0); _control_topics[1] = ORB_ID(actuator_controls_1); @@ -186,6 +187,10 @@ int UavcanNode::init(uavcan::NodeID node_id) if (ret < 0) return ret; + ret = _gnss_receiver.init(); + if (ret < 0) + return ret; + uavcan::protocol::SoftwareVersion swver; swver.major = 12; // TODO fill version info swver.minor = 34; diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 751a94a8a..126d44137 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -43,6 +43,7 @@ #include #include "esc_controller.hpp" +#include "gnss_receiver.hpp" /** * @file uavcan_main.hpp @@ -108,6 +109,7 @@ private: static UavcanNode *_instance; ///< singleton pointer Node _node; ///< library instance UavcanEscController _esc_controller; + UavcanGnssReceiver _gnss_receiver; MixerGroup *_mixers = nullptr; -- cgit v1.2.3 From 4cd66a3242aa2dfb03a3e58ffcc8d27e1350b7ac Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 2 Jul 2014 00:25:19 +0200 Subject: Fix sdlog2 GPS time copy for log_on_start situation --- src/modules/sdlog2/sdlog2.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 9b071ff99..f99aec34e 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -1070,7 +1070,7 @@ int sdlog2_thread_main(int argc, char *argv[]) if (log_on_start) { /* check GPS topic to get GPS time */ if (log_name_timestamp) { - if (copy_if_updated(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf_gps_pos)) { + if (!orb_copy(ORB_ID(vehicle_gps_position), subs.gps_pos_sub, &buf_gps_pos)) { gps_time = buf_gps_pos.time_gps_usec; } } -- cgit v1.2.3 From 756a2bb7e69113926551ee08aef0f301acaade1e Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 2 Jul 2014 09:35:50 +0200 Subject: hk micro pcb startup script --- ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb | 27 +++++++++++++++++++++++++++ 1 file changed, 27 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb new file mode 100644 index 000000000..42ec150c1 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb @@ -0,0 +1,27 @@ +#!nsh +# +# Hobbyking Micro Integrated PCB Quadcopter +# +# Anton Babushkin +# + +sh /etc/init.d/4001_quad_x + +if [ $DO_AUTOCONFIG == yes ] +then + param set MC_ROLL_P 7.0 + param set MC_ROLLRATE_P 0.1 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.003 + param set MC_PITCH_P 7.0 + param set MC_PITCHRATE_P 0.1 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.003 + param set MC_YAW_P 2.8 + param set MC_YAWRATE_P 0.2 + param set MC_YAWRATE_I 0.0 + param set MC_YAWRATE_D 0.0 +fi + +set PWM_MIN 1100 +set PWM_DISARMED 900 -- cgit v1.2.3 From 0d7ada14bb313a86cb49fb34888740486b47222d Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 2 Jul 2014 09:36:47 +0200 Subject: rc.autostart entry for hk micro pcb quad --- ROMFS/px4fmu_common/init.d/rc.autostart | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart index b365bd642..5d9e9502c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart +++ b/ROMFS/px4fmu_common/init.d/rc.autostart @@ -136,6 +136,11 @@ then sh /etc/init.d/4011_dji_f450 fi +if param compare SYS_AUTOSTART 4020 +then + sh /etc/init.d/4020_hk_micro_pcb +fi + # # Quad + # -- cgit v1.2.3 From f428ebb04f0610c31639d8fe6d121f632c1cad1b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 2 Jul 2014 11:39:56 +0200 Subject: gps: Comment-only fix --- src/drivers/gps/gps.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 1d8ef1b99..241e3bdf3 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -109,7 +109,7 @@ private: int _serial_fd; ///< serial interface to GPS unsigned _baudrate; ///< current baudrate char _port[20]; ///< device / serial port path - volatile int _task; //< worker task + volatile int _task; ///< worker task bool _healthy; ///< flag to signal if the GPS is ok bool _baudrate_changed; ///< flag to signal that the baudrate with the GPS has changed bool _mode_changed; ///< flag that the GPS mode has changed -- cgit v1.2.3 From 44b875428e2137da1cb8ceb1db446ddefc12b6bf Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 2 Jul 2014 14:15:04 +0200 Subject: delete mavlink header files --- .../mavlink/v1.0/ardupilotmega/ardupilotmega.h | 129 - .../include/mavlink/v1.0/ardupilotmega/mavlink.h | 27 - .../mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h | 353 -- .../mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs2.h | 329 -- .../ardupilotmega/mavlink_msg_airspeed_autocal.h | 473 -- .../v1.0/ardupilotmega/mavlink_msg_ap_adc.h | 329 -- .../ardupilotmega/mavlink_msg_compassmot_status.h | 329 -- .../v1.0/ardupilotmega/mavlink_msg_data16.h | 249 - .../v1.0/ardupilotmega/mavlink_msg_data32.h | 249 - .../v1.0/ardupilotmega/mavlink_msg_data64.h | 249 - .../v1.0/ardupilotmega/mavlink_msg_data96.h | 249 - .../ardupilotmega/mavlink_msg_digicam_configure.h | 449 -- .../ardupilotmega/mavlink_msg_digicam_control.h | 425 -- .../ardupilotmega/mavlink_msg_fence_fetch_point.h | 257 - .../v1.0/ardupilotmega/mavlink_msg_fence_point.h | 329 -- .../v1.0/ardupilotmega/mavlink_msg_fence_status.h | 281 - .../v1.0/ardupilotmega/mavlink_msg_hwstatus.h | 233 - .../v1.0/ardupilotmega/mavlink_msg_limits_status.h | 401 -- .../v1.0/ardupilotmega/mavlink_msg_meminfo.h | 233 - .../ardupilotmega/mavlink_msg_mount_configure.h | 329 -- .../v1.0/ardupilotmega/mavlink_msg_mount_control.h | 329 -- .../v1.0/ardupilotmega/mavlink_msg_mount_status.h | 305 - .../mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h | 353 -- .../ardupilotmega/mavlink_msg_rally_fetch_point.h | 257 - .../v1.0/ardupilotmega/mavlink_msg_rally_point.h | 425 -- .../v1.0/ardupilotmega/mavlink_msg_rangefinder.h | 233 - .../ardupilotmega/mavlink_msg_sensor_offsets.h | 473 -- .../ardupilotmega/mavlink_msg_set_mag_offsets.h | 305 - .../v1.0/ardupilotmega/mavlink_msg_simstate.h | 449 -- .../mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h | 257 - .../include/mavlink/v1.0/ardupilotmega/testsuite.h | 1542 ----- .../include/mavlink/v1.0/ardupilotmega/version.h | 12 - mavlink/include/mavlink/v1.0/autoquad/autoquad.h | 132 - mavlink/include/mavlink/v1.0/autoquad/mavlink.h | 27 - .../v1.0/autoquad/mavlink_msg_aq_telemetry_f.h | 689 --- mavlink/include/mavlink/v1.0/autoquad/testsuite.h | 118 - mavlink/include/mavlink/v1.0/autoquad/version.h | 12 - mavlink/include/mavlink/v1.0/checksum.h | 91 - mavlink/include/mavlink/v1.0/common/common.h | 670 --- mavlink/include/mavlink/v1.0/common/mavlink.h | 27 - .../mavlink/v1.0/common/mavlink_msg_attitude.h | 353 -- .../v1.0/common/mavlink_msg_attitude_quaternion.h | 377 -- .../mavlink/v1.0/common/mavlink_msg_auth_key.h | 209 - .../v1.0/common/mavlink_msg_battery_status.h | 449 -- .../common/mavlink_msg_change_operator_control.h | 273 - .../mavlink_msg_change_operator_control_ack.h | 257 - .../mavlink/v1.0/common/mavlink_msg_command_ack.h | 233 - .../mavlink/v1.0/common/mavlink_msg_command_long.h | 449 -- .../mavlink/v1.0/common/mavlink_msg_data_stream.h | 257 - .../mavlink_msg_data_transmission_handshake.h | 353 -- .../mavlink/v1.0/common/mavlink_msg_debug.h | 257 - .../mavlink/v1.0/common/mavlink_msg_debug_vect.h | 297 - .../v1.0/common/mavlink_msg_distance_sensor.h | 377 -- .../v1.0/common/mavlink_msg_encapsulated_data.h | 225 - .../common/mavlink_msg_file_transfer_dir_list.h | 249 - .../v1.0/common/mavlink_msg_file_transfer_res.h | 233 - .../v1.0/common/mavlink_msg_file_transfer_start.h | 297 - .../v1.0/common/mavlink_msg_global_position_int.h | 401 -- .../mavlink_msg_global_position_setpoint_int.h | 305 - .../mavlink_msg_global_vision_position_estimate.h | 353 -- .../mavlink/v1.0/common/mavlink_msg_gps2_raw.h | 473 -- .../v1.0/common/mavlink_msg_gps_global_origin.h | 257 - .../v1.0/common/mavlink_msg_gps_inject_data.h | 273 - .../mavlink/v1.0/common/mavlink_msg_gps_raw_int.h | 425 -- .../mavlink/v1.0/common/mavlink_msg_gps_status.h | 325 -- .../mavlink/v1.0/common/mavlink_msg_heartbeat.h | 326 -- .../mavlink/v1.0/common/mavlink_msg_highres_imu.h | 545 -- .../mavlink/v1.0/common/mavlink_msg_hil_controls.h | 449 -- .../mavlink/v1.0/common/mavlink_msg_hil_gps.h | 497 -- .../v1.0/common/mavlink_msg_hil_optical_flow.h | 377 -- .../v1.0/common/mavlink_msg_hil_rc_inputs_raw.h | 521 -- .../mavlink/v1.0/common/mavlink_msg_hil_sensor.h | 545 -- .../mavlink/v1.0/common/mavlink_msg_hil_state.h | 569 -- .../v1.0/common/mavlink_msg_hil_state_quaternion.h | 561 -- .../v1.0/common/mavlink_msg_local_position_ned.h | 353 -- ...k_msg_local_position_ned_system_global_offset.h | 353 -- .../common/mavlink_msg_local_position_setpoint.h | 305 - .../mavlink/v1.0/common/mavlink_msg_log_data.h | 273 - .../mavlink/v1.0/common/mavlink_msg_log_entry.h | 305 - .../mavlink/v1.0/common/mavlink_msg_log_erase.h | 233 - .../v1.0/common/mavlink_msg_log_request_data.h | 305 - .../v1.0/common/mavlink_msg_log_request_end.h | 233 - .../v1.0/common/mavlink_msg_log_request_list.h | 281 - .../v1.0/common/mavlink_msg_manual_control.h | 329 -- .../v1.0/common/mavlink_msg_manual_setpoint.h | 353 -- .../mavlink/v1.0/common/mavlink_msg_memory_vect.h | 273 - .../mavlink/v1.0/common/mavlink_msg_mission_ack.h | 257 - .../v1.0/common/mavlink_msg_mission_clear_all.h | 233 - .../v1.0/common/mavlink_msg_mission_count.h | 257 - .../v1.0/common/mavlink_msg_mission_current.h | 209 - .../mavlink/v1.0/common/mavlink_msg_mission_item.h | 521 -- .../v1.0/common/mavlink_msg_mission_item_reached.h | 209 - .../v1.0/common/mavlink_msg_mission_request.h | 257 - .../v1.0/common/mavlink_msg_mission_request_list.h | 233 - .../mavlink_msg_mission_request_partial_list.h | 281 - .../v1.0/common/mavlink_msg_mission_set_current.h | 257 - .../mavlink_msg_mission_write_partial_list.h | 281 - .../v1.0/common/mavlink_msg_named_value_float.h | 249 - .../v1.0/common/mavlink_msg_named_value_int.h | 249 - .../common/mavlink_msg_nav_controller_output.h | 377 -- .../v1.0/common/mavlink_msg_omnidirectional_flow.h | 322 -- .../mavlink/v1.0/common/mavlink_msg_optical_flow.h | 377 -- .../v1.0/common/mavlink_msg_param_request_list.h | 233 - .../v1.0/common/mavlink_msg_param_request_read.h | 273 - .../mavlink/v1.0/common/mavlink_msg_param_set.h | 297 - .../mavlink/v1.0/common/mavlink_msg_param_value.h | 297 - .../include/mavlink/v1.0/common/mavlink_msg_ping.h | 281 - .../mavlink/v1.0/common/mavlink_msg_power_status.h | 257 - .../mavlink/v1.0/common/mavlink_msg_radio_status.h | 353 -- .../mavlink/v1.0/common/mavlink_msg_raw_imu.h | 425 -- .../mavlink/v1.0/common/mavlink_msg_raw_pressure.h | 305 - .../mavlink/v1.0/common/mavlink_msg_rc_channels.h | 689 --- .../v1.0/common/mavlink_msg_rc_channels_override.h | 425 -- .../v1.0/common/mavlink_msg_rc_channels_raw.h | 449 -- .../v1.0/common/mavlink_msg_rc_channels_scaled.h | 449 -- .../v1.0/common/mavlink_msg_request_data_stream.h | 305 - ...link_msg_roll_pitch_yaw_rates_thrust_setpoint.h | 305 - ...link_msg_roll_pitch_yaw_speed_thrust_setpoint.h | 305 - .../mavlink_msg_roll_pitch_yaw_thrust_setpoint.h | 305 - .../v1.0/common/mavlink_msg_safety_allowed_area.h | 353 -- .../common/mavlink_msg_safety_set_allowed_area.h | 401 -- .../mavlink/v1.0/common/mavlink_msg_scaled_imu.h | 425 -- .../mavlink/v1.0/common/mavlink_msg_scaled_imu2.h | 425 -- .../v1.0/common/mavlink_msg_scaled_pressure.h | 281 - .../v1.0/common/mavlink_msg_serial_control.h | 321 -- .../v1.0/common/mavlink_msg_servo_output_raw.h | 425 -- .../mavlink_msg_set_global_position_setpoint_int.h | 305 - .../common/mavlink_msg_set_gps_global_origin.h | 281 - .../mavlink_msg_set_local_position_setpoint.h | 353 -- .../mavlink/v1.0/common/mavlink_msg_set_mode.h | 257 - .../common/mavlink_msg_set_quad_motors_setpoint.h | 305 - ..._msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h | 399 -- ...link_msg_set_quad_swarm_roll_pitch_yaw_thrust.h | 324 -- .../mavlink_msg_set_roll_pitch_yaw_speed_thrust.h | 329 -- .../common/mavlink_msg_set_roll_pitch_yaw_thrust.h | 329 -- .../v1.0/common/mavlink_msg_setpoint_6dof.h | 353 -- .../v1.0/common/mavlink_msg_setpoint_8dof.h | 401 -- .../mavlink/v1.0/common/mavlink_msg_sim_state.h | 689 --- .../v1.0/common/mavlink_msg_state_correction.h | 401 -- .../mavlink/v1.0/common/mavlink_msg_statustext.h | 225 - .../mavlink/v1.0/common/mavlink_msg_sys_status.h | 497 -- .../mavlink/v1.0/common/mavlink_msg_system_time.h | 233 - .../mavlink/v1.0/common/mavlink_msg_vfr_hud.h | 329 -- .../common/mavlink_msg_vicon_position_estimate.h | 353 -- .../common/mavlink_msg_vision_position_estimate.h | 353 -- .../common/mavlink_msg_vision_speed_estimate.h | 281 - mavlink/include/mavlink/v1.0/common/testsuite.h | 5872 -------------------- mavlink/include/mavlink/v1.0/common/version.h | 12 - .../include/mavlink/v1.0/matrixpilot/matrixpilot.h | 142 - mavlink/include/mavlink/v1.0/matrixpilot/mavlink.h | 27 - .../v1.0/matrixpilot/mavlink_msg_airspeeds.h | 353 -- .../v1.0/matrixpilot/mavlink_msg_altitudes.h | 353 -- .../mavlink_msg_flexifunction_buffer_function.h | 345 -- ...mavlink_msg_flexifunction_buffer_function_ack.h | 281 - .../mavlink_msg_flexifunction_command.h | 257 - .../mavlink_msg_flexifunction_command_ack.h | 233 - .../mavlink_msg_flexifunction_directory.h | 321 -- .../mavlink_msg_flexifunction_directory_ack.h | 329 -- .../mavlink_msg_flexifunction_read_req.h | 281 - .../matrixpilot/mavlink_msg_flexifunction_set.h | 233 - .../matrixpilot/mavlink_msg_serial_udb_extra_f13.h | 281 - .../matrixpilot/mavlink_msg_serial_udb_extra_f14.h | 449 -- .../matrixpilot/mavlink_msg_serial_udb_extra_f15.h | 234 - .../matrixpilot/mavlink_msg_serial_udb_extra_f16.h | 234 - .../mavlink_msg_serial_udb_extra_f2_a.h | 857 --- .../mavlink_msg_serial_udb_extra_f2_b.h | 977 ---- .../matrixpilot/mavlink_msg_serial_udb_extra_f4.h | 425 -- .../matrixpilot/mavlink_msg_serial_udb_extra_f5.h | 329 -- .../matrixpilot/mavlink_msg_serial_udb_extra_f6.h | 305 - .../matrixpilot/mavlink_msg_serial_udb_extra_f7.h | 329 -- .../matrixpilot/mavlink_msg_serial_udb_extra_f8.h | 353 -- .../include/mavlink/v1.0/matrixpilot/testsuite.h | 1240 ----- mavlink/include/mavlink/v1.0/matrixpilot/version.h | 12 - mavlink/include/mavlink/v1.0/mavlink_conversions.h | 135 - mavlink/include/mavlink/v1.0/mavlink_helpers.h | 574 -- .../mavlink/v1.0/mavlink_protobuf_manager.hpp | 377 -- mavlink/include/mavlink/v1.0/mavlink_types.h | 161 - mavlink/include/mavlink/v1.0/pixhawk/mavlink.h | 27 - .../v1.0/pixhawk/mavlink_msg_attitude_control.h | 401 -- .../v1.0/pixhawk/mavlink_msg_brief_feature.h | 369 -- .../v1.0/pixhawk/mavlink_msg_image_available.h | 737 --- .../pixhawk/mavlink_msg_image_trigger_control.h | 209 - .../v1.0/pixhawk/mavlink_msg_image_triggered.h | 473 -- .../mavlink/v1.0/pixhawk/mavlink_msg_marker.h | 353 -- .../v1.0/pixhawk/mavlink_msg_pattern_detected.h | 273 - .../v1.0/pixhawk/mavlink_msg_point_of_interest.h | 369 -- .../mavlink_msg_point_of_interest_connection.h | 441 -- .../mavlink_msg_position_control_setpoint.h | 305 - .../mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h | 353 -- .../v1.0/pixhawk/mavlink_msg_set_cam_shutter.h | 329 -- .../mavlink_msg_set_position_control_offset.h | 329 -- .../v1.0/pixhawk/mavlink_msg_watchdog_command.h | 281 - .../v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h | 233 - .../pixhawk/mavlink_msg_watchdog_process_info.h | 298 - .../pixhawk/mavlink_msg_watchdog_process_status.h | 329 -- mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h | 136 - mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h | 3663 ------------ mavlink/include/mavlink/v1.0/pixhawk/testsuite.h | 996 ---- mavlink/include/mavlink/v1.0/pixhawk/version.h | 12 - mavlink/include/mavlink/v1.0/protocol.h | 328 -- mavlink/include/mavlink/v1.0/sensesoar/mavlink.h | 27 - .../v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h | 253 - .../v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h | 253 - .../v1.0/sensesoar/mavlink_msg_filt_rot_vel.h | 219 - .../mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h | 254 - .../v1.0/sensesoar/mavlink_msg_obs_air_temp.h | 219 - .../v1.0/sensesoar/mavlink_msg_obs_air_velocity.h | 287 - .../v1.0/sensesoar/mavlink_msg_obs_attitude.h | 219 - .../mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h | 254 - .../v1.0/sensesoar/mavlink_msg_obs_position.h | 287 - .../mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h | 219 - .../v1.0/sensesoar/mavlink_msg_obs_velocity.h | 219 - .../mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h | 219 - .../mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h | 279 - .../mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h | 321 -- mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h | 77 - mavlink/include/mavlink/v1.0/sensesoar/testsuite.h | 676 --- mavlink/include/mavlink/v1.0/sensesoar/version.h | 12 - 218 files changed, 80550 deletions(-) delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs2.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_compassmot_status.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h delete mode 100644 mavlink/include/mavlink/v1.0/ardupilotmega/version.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/autoquad.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/mavlink.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/testsuite.h delete mode 100644 mavlink/include/mavlink/v1.0/autoquad/version.h delete mode 100644 mavlink/include/mavlink/v1.0/checksum.h delete mode 100644 mavlink/include/mavlink/v1.0/common/common.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_power_status.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_serial_control.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h delete mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h delete mode 100644 mavlink/include/mavlink/v1.0/common/testsuite.h delete mode 100644 mavlink/include/mavlink/v1.0/common/version.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/matrixpilot.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/testsuite.h delete mode 100644 mavlink/include/mavlink/v1.0/matrixpilot/version.h delete mode 100644 mavlink/include/mavlink/v1.0/mavlink_conversions.h delete mode 100644 mavlink/include/mavlink/v1.0/mavlink_helpers.h delete mode 100644 mavlink/include/mavlink/v1.0/mavlink_protobuf_manager.hpp delete mode 100644 mavlink/include/mavlink/v1.0/mavlink_types.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/testsuite.h delete mode 100644 mavlink/include/mavlink/v1.0/pixhawk/version.h delete mode 100644 mavlink/include/mavlink/v1.0/protocol.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/testsuite.h delete mode 100644 mavlink/include/mavlink/v1.0/sensesoar/version.h diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h deleted file mode 100644 index c887dc68a..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h +++ /dev/null @@ -1,129 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from ardupilotmega.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef ARDUPILOTMEGA_H -#define ARDUPILOTMEGA_H - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} -#endif - -#ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_ARDUPILOTMEGA - -// ENUM DEFINITIONS - - -/** @brief */ -#ifndef HAVE_ENUM_LIMITS_STATE -#define HAVE_ENUM_LIMITS_STATE -enum LIMITS_STATE -{ - LIMITS_INIT=0, /* pre-initialization | */ - LIMITS_DISABLED=1, /* disabled | */ - LIMITS_ENABLED=2, /* checking limits | */ - LIMITS_TRIGGERED=3, /* a limit has been breached | */ - LIMITS_RECOVERING=4, /* taking action eg. RTL | */ - LIMITS_RECOVERED=5, /* we're no longer in breach of a limit | */ - LIMITS_STATE_ENUM_END=6, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_LIMIT_MODULE -#define HAVE_ENUM_LIMIT_MODULE -enum LIMIT_MODULE -{ - LIMIT_GPSLOCK=1, /* pre-initialization | */ - LIMIT_GEOFENCE=2, /* disabled | */ - LIMIT_ALTITUDE=4, /* checking limits | */ - LIMIT_MODULE_ENUM_END=5, /* | */ -}; -#endif - -/** @brief Flags in RALLY_POINT message */ -#ifndef HAVE_ENUM_RALLY_FLAGS -#define HAVE_ENUM_RALLY_FLAGS -enum RALLY_FLAGS -{ - FAVORABLE_WIND=1, /* Flag set when requiring favorable winds for landing. | */ - LAND_IMMEDIATELY=2, /* Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. | */ - RALLY_FLAGS_ENUM_END=3, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_PARACHUTE_ACTION -#define HAVE_ENUM_PARACHUTE_ACTION -enum PARACHUTE_ACTION -{ - PARACHUTE_DISABLE=0, /* Disable parachute release | */ - PARACHUTE_ENABLE=1, /* Enable parachute release | */ - PARACHUTE_RELEASE=2, /* Release parachute | */ - PARACHUTE_ACTION_ENUM_END=3, /* | */ -}; -#endif - -#include "../common/common.h" - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_sensor_offsets.h" -#include "./mavlink_msg_set_mag_offsets.h" -#include "./mavlink_msg_meminfo.h" -#include "./mavlink_msg_ap_adc.h" -#include "./mavlink_msg_digicam_configure.h" -#include "./mavlink_msg_digicam_control.h" -#include "./mavlink_msg_mount_configure.h" -#include "./mavlink_msg_mount_control.h" -#include "./mavlink_msg_mount_status.h" -#include "./mavlink_msg_fence_point.h" -#include "./mavlink_msg_fence_fetch_point.h" -#include "./mavlink_msg_fence_status.h" -#include "./mavlink_msg_ahrs.h" -#include "./mavlink_msg_simstate.h" -#include "./mavlink_msg_hwstatus.h" -#include "./mavlink_msg_radio.h" -#include "./mavlink_msg_limits_status.h" -#include "./mavlink_msg_wind.h" -#include "./mavlink_msg_data16.h" -#include "./mavlink_msg_data32.h" -#include "./mavlink_msg_data64.h" -#include "./mavlink_msg_data96.h" -#include "./mavlink_msg_rangefinder.h" -#include "./mavlink_msg_airspeed_autocal.h" -#include "./mavlink_msg_rally_point.h" -#include "./mavlink_msg_rally_fetch_point.h" -#include "./mavlink_msg_compassmot_status.h" -#include "./mavlink_msg_ahrs2.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // ARDUPILOTMEGA_H diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink.h deleted file mode 100644 index 551938f04..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink.h +++ /dev/null @@ -1,27 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from ardupilotmega.xml - * @see http://pixhawk.ethz.ch/software/mavlink - */ -#ifndef MAVLINK_H -#define MAVLINK_H - -#ifndef MAVLINK_STX -#define MAVLINK_STX 254 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#include "version.h" -#include "ardupilotmega.h" - -#endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h deleted file mode 100644 index 50ddc79e5..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE AHRS PACKING - -#define MAVLINK_MSG_ID_AHRS 163 - -typedef struct __mavlink_ahrs_t -{ - float omegaIx; ///< X gyro drift estimate rad/s - float omegaIy; ///< Y gyro drift estimate rad/s - float omegaIz; ///< Z gyro drift estimate rad/s - float accel_weight; ///< average accel_weight - float renorm_val; ///< average renormalisation value - float error_rp; ///< average error_roll_pitch value - float error_yaw; ///< average error_yaw value -} mavlink_ahrs_t; - -#define MAVLINK_MSG_ID_AHRS_LEN 28 -#define MAVLINK_MSG_ID_163_LEN 28 - -#define MAVLINK_MSG_ID_AHRS_CRC 127 -#define MAVLINK_MSG_ID_163_CRC 127 - - - -#define MAVLINK_MESSAGE_INFO_AHRS { \ - "AHRS", \ - 7, \ - { { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \ - { "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \ - { "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \ - { "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \ - { "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \ - { "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \ - { "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \ - } \ -} - - -/** - * @brief Pack a ahrs message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param omegaIx X gyro drift estimate rad/s - * @param omegaIy Y gyro drift estimate rad/s - * @param omegaIz Z gyro drift estimate rad/s - * @param accel_weight average accel_weight - * @param renorm_val average renormalisation value - * @param error_rp average error_roll_pitch value - * @param error_yaw average error_yaw value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AHRS_LEN]; - _mav_put_float(buf, 0, omegaIx); - _mav_put_float(buf, 4, omegaIy); - _mav_put_float(buf, 8, omegaIz); - _mav_put_float(buf, 12, accel_weight); - _mav_put_float(buf, 16, renorm_val); - _mav_put_float(buf, 20, error_rp); - _mav_put_float(buf, 24, error_yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS_LEN); -#else - mavlink_ahrs_t packet; - packet.omegaIx = omegaIx; - packet.omegaIy = omegaIy; - packet.omegaIz = omegaIz; - packet.accel_weight = accel_weight; - packet.renorm_val = renorm_val; - packet.error_rp = error_rp; - packet.error_yaw = error_yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AHRS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS_LEN); -#endif -} - -/** - * @brief Pack a ahrs message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param omegaIx X gyro drift estimate rad/s - * @param omegaIy Y gyro drift estimate rad/s - * @param omegaIz Z gyro drift estimate rad/s - * @param accel_weight average accel_weight - * @param renorm_val average renormalisation value - * @param error_rp average error_roll_pitch value - * @param error_yaw average error_yaw value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AHRS_LEN]; - _mav_put_float(buf, 0, omegaIx); - _mav_put_float(buf, 4, omegaIy); - _mav_put_float(buf, 8, omegaIz); - _mav_put_float(buf, 12, accel_weight); - _mav_put_float(buf, 16, renorm_val); - _mav_put_float(buf, 20, error_rp); - _mav_put_float(buf, 24, error_yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS_LEN); -#else - mavlink_ahrs_t packet; - packet.omegaIx = omegaIx; - packet.omegaIy = omegaIy; - packet.omegaIz = omegaIz; - packet.accel_weight = accel_weight; - packet.renorm_val = renorm_val; - packet.error_rp = error_rp; - packet.error_yaw = error_yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AHRS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS_LEN); -#endif -} - -/** - * @brief Encode a ahrs struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ahrs C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs) -{ - return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw); -} - -/** - * @brief Encode a ahrs struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ahrs C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ahrs_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs) -{ - return mavlink_msg_ahrs_pack_chan(system_id, component_id, chan, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw); -} - -/** - * @brief Send a ahrs message - * @param chan MAVLink channel to send the message - * - * @param omegaIx X gyro drift estimate rad/s - * @param omegaIy Y gyro drift estimate rad/s - * @param omegaIz Z gyro drift estimate rad/s - * @param accel_weight average accel_weight - * @param renorm_val average renormalisation value - * @param error_rp average error_roll_pitch value - * @param error_yaw average error_yaw value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AHRS_LEN]; - _mav_put_float(buf, 0, omegaIx); - _mav_put_float(buf, 4, omegaIy); - _mav_put_float(buf, 8, omegaIz); - _mav_put_float(buf, 12, accel_weight); - _mav_put_float(buf, 16, renorm_val); - _mav_put_float(buf, 20, error_rp); - _mav_put_float(buf, 24, error_yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_LEN); -#endif -#else - mavlink_ahrs_t packet; - packet.omegaIx = omegaIx; - packet.omegaIy = omegaIy; - packet.omegaIz = omegaIz; - packet.accel_weight = accel_weight; - packet.renorm_val = renorm_val; - packet.error_rp = error_rp; - packet.error_yaw = error_yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, MAVLINK_MSG_ID_AHRS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_AHRS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_ahrs_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, omegaIx); - _mav_put_float(buf, 4, omegaIy); - _mav_put_float(buf, 8, omegaIz); - _mav_put_float(buf, 12, accel_weight); - _mav_put_float(buf, 16, renorm_val); - _mav_put_float(buf, 20, error_rp); - _mav_put_float(buf, 24, error_yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_LEN); -#endif -#else - mavlink_ahrs_t *packet = (mavlink_ahrs_t *)msgbuf; - packet->omegaIx = omegaIx; - packet->omegaIy = omegaIy; - packet->omegaIz = omegaIz; - packet->accel_weight = accel_weight; - packet->renorm_val = renorm_val; - packet->error_rp = error_rp; - packet->error_yaw = error_yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)packet, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)packet, MAVLINK_MSG_ID_AHRS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE AHRS UNPACKING - - -/** - * @brief Get field omegaIx from ahrs message - * - * @return X gyro drift estimate rad/s - */ -static inline float mavlink_msg_ahrs_get_omegaIx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field omegaIy from ahrs message - * - * @return Y gyro drift estimate rad/s - */ -static inline float mavlink_msg_ahrs_get_omegaIy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field omegaIz from ahrs message - * - * @return Z gyro drift estimate rad/s - */ -static inline float mavlink_msg_ahrs_get_omegaIz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field accel_weight from ahrs message - * - * @return average accel_weight - */ -static inline float mavlink_msg_ahrs_get_accel_weight(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field renorm_val from ahrs message - * - * @return average renormalisation value - */ -static inline float mavlink_msg_ahrs_get_renorm_val(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field error_rp from ahrs message - * - * @return average error_roll_pitch value - */ -static inline float mavlink_msg_ahrs_get_error_rp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field error_yaw from ahrs message - * - * @return average error_yaw value - */ -static inline float mavlink_msg_ahrs_get_error_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a ahrs message into a struct - * - * @param msg The message to decode - * @param ahrs C-struct to decode the message contents into - */ -static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink_ahrs_t* ahrs) -{ -#if MAVLINK_NEED_BYTE_SWAP - ahrs->omegaIx = mavlink_msg_ahrs_get_omegaIx(msg); - ahrs->omegaIy = mavlink_msg_ahrs_get_omegaIy(msg); - ahrs->omegaIz = mavlink_msg_ahrs_get_omegaIz(msg); - ahrs->accel_weight = mavlink_msg_ahrs_get_accel_weight(msg); - ahrs->renorm_val = mavlink_msg_ahrs_get_renorm_val(msg); - ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg); - ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg); -#else - memcpy(ahrs, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AHRS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs2.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs2.h deleted file mode 100644 index 33e006688..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs2.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE AHRS2 PACKING - -#define MAVLINK_MSG_ID_AHRS2 178 - -typedef struct __mavlink_ahrs2_t -{ - float roll; ///< Roll angle (rad) - float pitch; ///< Pitch angle (rad) - float yaw; ///< Yaw angle (rad) - float altitude; ///< Altitude (MSL) - int32_t lat; ///< Latitude in degrees * 1E7 - int32_t lng; ///< Longitude in degrees * 1E7 -} mavlink_ahrs2_t; - -#define MAVLINK_MSG_ID_AHRS2_LEN 24 -#define MAVLINK_MSG_ID_178_LEN 24 - -#define MAVLINK_MSG_ID_AHRS2_CRC 47 -#define MAVLINK_MSG_ID_178_CRC 47 - - - -#define MAVLINK_MESSAGE_INFO_AHRS2 { \ - "AHRS2", \ - 6, \ - { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs2_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs2_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs2_t, yaw) }, \ - { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs2_t, altitude) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs2_t, lat) }, \ - { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs2_t, lng) }, \ - } \ -} - - -/** - * @brief Pack a ahrs2 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param altitude Altitude (MSL) - * @param lat Latitude in degrees * 1E7 - * @param lng Longitude in degrees * 1E7 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ahrs2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AHRS2_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, altitude); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lng); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS2_LEN); -#else - mavlink_ahrs2_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.altitude = altitude; - packet.lat = lat; - packet.lng = lng; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AHRS2; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS2_LEN); -#endif -} - -/** - * @brief Pack a ahrs2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param altitude Altitude (MSL) - * @param lat Latitude in degrees * 1E7 - * @param lng Longitude in degrees * 1E7 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ahrs2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float roll,float pitch,float yaw,float altitude,int32_t lat,int32_t lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AHRS2_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, altitude); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lng); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS2_LEN); -#else - mavlink_ahrs2_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.altitude = altitude; - packet.lat = lat; - packet.lng = lng; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AHRS2; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS2_LEN); -#endif -} - -/** - * @brief Encode a ahrs2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ahrs2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ahrs2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs2_t* ahrs2) -{ - return mavlink_msg_ahrs2_pack(system_id, component_id, msg, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng); -} - -/** - * @brief Encode a ahrs2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ahrs2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ahrs2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs2_t* ahrs2) -{ - return mavlink_msg_ahrs2_pack_chan(system_id, component_id, chan, msg, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng); -} - -/** - * @brief Send a ahrs2 message - * @param chan MAVLink channel to send the message - * - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param altitude Altitude (MSL) - * @param lat Latitude in degrees * 1E7 - * @param lng Longitude in degrees * 1E7 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_ahrs2_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AHRS2_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, altitude); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lng); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_LEN); -#endif -#else - mavlink_ahrs2_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.altitude = altitude; - packet.lat = lat; - packet.lng = lng; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)&packet, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)&packet, MAVLINK_MSG_ID_AHRS2_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_AHRS2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_ahrs2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, altitude); - _mav_put_int32_t(buf, 16, lat); - _mav_put_int32_t(buf, 20, lng); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_LEN); -#endif -#else - mavlink_ahrs2_t *packet = (mavlink_ahrs2_t *)msgbuf; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->altitude = altitude; - packet->lat = lat; - packet->lng = lng; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)packet, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)packet, MAVLINK_MSG_ID_AHRS2_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE AHRS2 UNPACKING - - -/** - * @brief Get field roll from ahrs2 message - * - * @return Roll angle (rad) - */ -static inline float mavlink_msg_ahrs2_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field pitch from ahrs2 message - * - * @return Pitch angle (rad) - */ -static inline float mavlink_msg_ahrs2_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field yaw from ahrs2 message - * - * @return Yaw angle (rad) - */ -static inline float mavlink_msg_ahrs2_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field altitude from ahrs2 message - * - * @return Altitude (MSL) - */ -static inline float mavlink_msg_ahrs2_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field lat from ahrs2 message - * - * @return Latitude in degrees * 1E7 - */ -static inline int32_t mavlink_msg_ahrs2_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field lng from ahrs2 message - * - * @return Longitude in degrees * 1E7 - */ -static inline int32_t mavlink_msg_ahrs2_get_lng(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Decode a ahrs2 message into a struct - * - * @param msg The message to decode - * @param ahrs2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_ahrs2_decode(const mavlink_message_t* msg, mavlink_ahrs2_t* ahrs2) -{ -#if MAVLINK_NEED_BYTE_SWAP - ahrs2->roll = mavlink_msg_ahrs2_get_roll(msg); - ahrs2->pitch = mavlink_msg_ahrs2_get_pitch(msg); - ahrs2->yaw = mavlink_msg_ahrs2_get_yaw(msg); - ahrs2->altitude = mavlink_msg_ahrs2_get_altitude(msg); - ahrs2->lat = mavlink_msg_ahrs2_get_lat(msg); - ahrs2->lng = mavlink_msg_ahrs2_get_lng(msg); -#else - memcpy(ahrs2, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AHRS2_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h deleted file mode 100644 index 521831c8f..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_airspeed_autocal.h +++ /dev/null @@ -1,473 +0,0 @@ -// MESSAGE AIRSPEED_AUTOCAL PACKING - -#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL 174 - -typedef struct __mavlink_airspeed_autocal_t -{ - float vx; ///< GPS velocity north m/s - float vy; ///< GPS velocity east m/s - float vz; ///< GPS velocity down m/s - float diff_pressure; ///< Differential pressure pascals - float EAS2TAS; ///< Estimated to true airspeed ratio - float ratio; ///< Airspeed ratio - float state_x; ///< EKF state x - float state_y; ///< EKF state y - float state_z; ///< EKF state z - float Pax; ///< EKF Pax - float Pby; ///< EKF Pby - float Pcz; ///< EKF Pcz -} mavlink_airspeed_autocal_t; - -#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN 48 -#define MAVLINK_MSG_ID_174_LEN 48 - -#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC 167 -#define MAVLINK_MSG_ID_174_CRC 167 - - - -#define MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL { \ - "AIRSPEED_AUTOCAL", \ - 12, \ - { { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_airspeed_autocal_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_airspeed_autocal_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_airspeed_autocal_t, vz) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_airspeed_autocal_t, diff_pressure) }, \ - { "EAS2TAS", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_airspeed_autocal_t, EAS2TAS) }, \ - { "ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_airspeed_autocal_t, ratio) }, \ - { "state_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_airspeed_autocal_t, state_x) }, \ - { "state_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_airspeed_autocal_t, state_y) }, \ - { "state_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_airspeed_autocal_t, state_z) }, \ - { "Pax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_airspeed_autocal_t, Pax) }, \ - { "Pby", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_airspeed_autocal_t, Pby) }, \ - { "Pcz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_airspeed_autocal_t, Pcz) }, \ - } \ -} - - -/** - * @brief Pack a airspeed_autocal message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param vx GPS velocity north m/s - * @param vy GPS velocity east m/s - * @param vz GPS velocity down m/s - * @param diff_pressure Differential pressure pascals - * @param EAS2TAS Estimated to true airspeed ratio - * @param ratio Airspeed ratio - * @param state_x EKF state x - * @param state_y EKF state y - * @param state_z EKF state z - * @param Pax EKF Pax - * @param Pby EKF Pby - * @param Pcz EKF Pcz - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_airspeed_autocal_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN]; - _mav_put_float(buf, 0, vx); - _mav_put_float(buf, 4, vy); - _mav_put_float(buf, 8, vz); - _mav_put_float(buf, 12, diff_pressure); - _mav_put_float(buf, 16, EAS2TAS); - _mav_put_float(buf, 20, ratio); - _mav_put_float(buf, 24, state_x); - _mav_put_float(buf, 28, state_y); - _mav_put_float(buf, 32, state_z); - _mav_put_float(buf, 36, Pax); - _mav_put_float(buf, 40, Pby); - _mav_put_float(buf, 44, Pcz); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#else - mavlink_airspeed_autocal_t packet; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.diff_pressure = diff_pressure; - packet.EAS2TAS = EAS2TAS; - packet.ratio = ratio; - packet.state_x = state_x; - packet.state_y = state_y; - packet.state_z = state_z; - packet.Pax = Pax; - packet.Pby = Pby; - packet.Pcz = Pcz; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#endif -} - -/** - * @brief Pack a airspeed_autocal message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vx GPS velocity north m/s - * @param vy GPS velocity east m/s - * @param vz GPS velocity down m/s - * @param diff_pressure Differential pressure pascals - * @param EAS2TAS Estimated to true airspeed ratio - * @param ratio Airspeed ratio - * @param state_x EKF state x - * @param state_y EKF state y - * @param state_z EKF state z - * @param Pax EKF Pax - * @param Pby EKF Pby - * @param Pcz EKF Pcz - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_airspeed_autocal_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float vx,float vy,float vz,float diff_pressure,float EAS2TAS,float ratio,float state_x,float state_y,float state_z,float Pax,float Pby,float Pcz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN]; - _mav_put_float(buf, 0, vx); - _mav_put_float(buf, 4, vy); - _mav_put_float(buf, 8, vz); - _mav_put_float(buf, 12, diff_pressure); - _mav_put_float(buf, 16, EAS2TAS); - _mav_put_float(buf, 20, ratio); - _mav_put_float(buf, 24, state_x); - _mav_put_float(buf, 28, state_y); - _mav_put_float(buf, 32, state_z); - _mav_put_float(buf, 36, Pax); - _mav_put_float(buf, 40, Pby); - _mav_put_float(buf, 44, Pcz); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#else - mavlink_airspeed_autocal_t packet; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.diff_pressure = diff_pressure; - packet.EAS2TAS = EAS2TAS; - packet.ratio = ratio; - packet.state_x = state_x; - packet.state_y = state_y; - packet.state_z = state_z; - packet.Pax = Pax; - packet.Pby = Pby; - packet.Pcz = Pcz; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#endif -} - -/** - * @brief Encode a airspeed_autocal struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param airspeed_autocal C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_airspeed_autocal_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal) -{ - return mavlink_msg_airspeed_autocal_pack(system_id, component_id, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz); -} - -/** - * @brief Encode a airspeed_autocal struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param airspeed_autocal C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_airspeed_autocal_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal) -{ - return mavlink_msg_airspeed_autocal_pack_chan(system_id, component_id, chan, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz); -} - -/** - * @brief Send a airspeed_autocal message - * @param chan MAVLink channel to send the message - * - * @param vx GPS velocity north m/s - * @param vy GPS velocity east m/s - * @param vz GPS velocity down m/s - * @param diff_pressure Differential pressure pascals - * @param EAS2TAS Estimated to true airspeed ratio - * @param ratio Airspeed ratio - * @param state_x EKF state x - * @param state_y EKF state y - * @param state_z EKF state z - * @param Pax EKF Pax - * @param Pby EKF Pby - * @param Pcz EKF Pcz - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_airspeed_autocal_send(mavlink_channel_t chan, float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN]; - _mav_put_float(buf, 0, vx); - _mav_put_float(buf, 4, vy); - _mav_put_float(buf, 8, vz); - _mav_put_float(buf, 12, diff_pressure); - _mav_put_float(buf, 16, EAS2TAS); - _mav_put_float(buf, 20, ratio); - _mav_put_float(buf, 24, state_x); - _mav_put_float(buf, 28, state_y); - _mav_put_float(buf, 32, state_z); - _mav_put_float(buf, 36, Pax); - _mav_put_float(buf, 40, Pby); - _mav_put_float(buf, 44, Pcz); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#endif -#else - mavlink_airspeed_autocal_t packet; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.diff_pressure = diff_pressure; - packet.EAS2TAS = EAS2TAS; - packet.ratio = ratio; - packet.state_x = state_x; - packet.state_y = state_y; - packet.state_z = state_z; - packet.Pax = Pax; - packet.Pby = Pby; - packet.Pcz = Pcz; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_airspeed_autocal_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, vx); - _mav_put_float(buf, 4, vy); - _mav_put_float(buf, 8, vz); - _mav_put_float(buf, 12, diff_pressure); - _mav_put_float(buf, 16, EAS2TAS); - _mav_put_float(buf, 20, ratio); - _mav_put_float(buf, 24, state_x); - _mav_put_float(buf, 28, state_y); - _mav_put_float(buf, 32, state_z); - _mav_put_float(buf, 36, Pax); - _mav_put_float(buf, 40, Pby); - _mav_put_float(buf, 44, Pcz); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#endif -#else - mavlink_airspeed_autocal_t *packet = (mavlink_airspeed_autocal_t *)msgbuf; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->diff_pressure = diff_pressure; - packet->EAS2TAS = EAS2TAS; - packet->ratio = ratio; - packet->state_x = state_x; - packet->state_y = state_y; - packet->state_z = state_z; - packet->Pax = Pax; - packet->Pby = Pby; - packet->Pcz = Pcz; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE AIRSPEED_AUTOCAL UNPACKING - - -/** - * @brief Get field vx from airspeed_autocal message - * - * @return GPS velocity north m/s - */ -static inline float mavlink_msg_airspeed_autocal_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field vy from airspeed_autocal message - * - * @return GPS velocity east m/s - */ -static inline float mavlink_msg_airspeed_autocal_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field vz from airspeed_autocal message - * - * @return GPS velocity down m/s - */ -static inline float mavlink_msg_airspeed_autocal_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field diff_pressure from airspeed_autocal message - * - * @return Differential pressure pascals - */ -static inline float mavlink_msg_airspeed_autocal_get_diff_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field EAS2TAS from airspeed_autocal message - * - * @return Estimated to true airspeed ratio - */ -static inline float mavlink_msg_airspeed_autocal_get_EAS2TAS(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field ratio from airspeed_autocal message - * - * @return Airspeed ratio - */ -static inline float mavlink_msg_airspeed_autocal_get_ratio(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field state_x from airspeed_autocal message - * - * @return EKF state x - */ -static inline float mavlink_msg_airspeed_autocal_get_state_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field state_y from airspeed_autocal message - * - * @return EKF state y - */ -static inline float mavlink_msg_airspeed_autocal_get_state_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field state_z from airspeed_autocal message - * - * @return EKF state z - */ -static inline float mavlink_msg_airspeed_autocal_get_state_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field Pax from airspeed_autocal message - * - * @return EKF Pax - */ -static inline float mavlink_msg_airspeed_autocal_get_Pax(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field Pby from airspeed_autocal message - * - * @return EKF Pby - */ -static inline float mavlink_msg_airspeed_autocal_get_Pby(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field Pcz from airspeed_autocal message - * - * @return EKF Pcz - */ -static inline float mavlink_msg_airspeed_autocal_get_Pcz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Decode a airspeed_autocal message into a struct - * - * @param msg The message to decode - * @param airspeed_autocal C-struct to decode the message contents into - */ -static inline void mavlink_msg_airspeed_autocal_decode(const mavlink_message_t* msg, mavlink_airspeed_autocal_t* airspeed_autocal) -{ -#if MAVLINK_NEED_BYTE_SWAP - airspeed_autocal->vx = mavlink_msg_airspeed_autocal_get_vx(msg); - airspeed_autocal->vy = mavlink_msg_airspeed_autocal_get_vy(msg); - airspeed_autocal->vz = mavlink_msg_airspeed_autocal_get_vz(msg); - airspeed_autocal->diff_pressure = mavlink_msg_airspeed_autocal_get_diff_pressure(msg); - airspeed_autocal->EAS2TAS = mavlink_msg_airspeed_autocal_get_EAS2TAS(msg); - airspeed_autocal->ratio = mavlink_msg_airspeed_autocal_get_ratio(msg); - airspeed_autocal->state_x = mavlink_msg_airspeed_autocal_get_state_x(msg); - airspeed_autocal->state_y = mavlink_msg_airspeed_autocal_get_state_y(msg); - airspeed_autocal->state_z = mavlink_msg_airspeed_autocal_get_state_z(msg); - airspeed_autocal->Pax = mavlink_msg_airspeed_autocal_get_Pax(msg); - airspeed_autocal->Pby = mavlink_msg_airspeed_autocal_get_Pby(msg); - airspeed_autocal->Pcz = mavlink_msg_airspeed_autocal_get_Pcz(msg); -#else - memcpy(airspeed_autocal, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h deleted file mode 100644 index 3c18e644e..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE AP_ADC PACKING - -#define MAVLINK_MSG_ID_AP_ADC 153 - -typedef struct __mavlink_ap_adc_t -{ - uint16_t adc1; ///< ADC output 1 - uint16_t adc2; ///< ADC output 2 - uint16_t adc3; ///< ADC output 3 - uint16_t adc4; ///< ADC output 4 - uint16_t adc5; ///< ADC output 5 - uint16_t adc6; ///< ADC output 6 -} mavlink_ap_adc_t; - -#define MAVLINK_MSG_ID_AP_ADC_LEN 12 -#define MAVLINK_MSG_ID_153_LEN 12 - -#define MAVLINK_MSG_ID_AP_ADC_CRC 188 -#define MAVLINK_MSG_ID_153_CRC 188 - - - -#define MAVLINK_MESSAGE_INFO_AP_ADC { \ - "AP_ADC", \ - 6, \ - { { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \ - { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \ - { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \ - { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \ - { "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \ - { "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \ - } \ -} - - -/** - * @brief Pack a ap_adc message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param adc1 ADC output 1 - * @param adc2 ADC output 2 - * @param adc3 ADC output 3 - * @param adc4 ADC output 4 - * @param adc5 ADC output 5 - * @param adc6 ADC output 6 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AP_ADC_LEN]; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, adc5); - _mav_put_uint16_t(buf, 10, adc6); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AP_ADC_LEN); -#else - mavlink_ap_adc_t packet; - packet.adc1 = adc1; - packet.adc2 = adc2; - packet.adc3 = adc3; - packet.adc4 = adc4; - packet.adc5 = adc5; - packet.adc6 = adc6; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AP_ADC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AP_ADC; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AP_ADC_LEN); -#endif -} - -/** - * @brief Pack a ap_adc message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param adc1 ADC output 1 - * @param adc2 ADC output 2 - * @param adc3 ADC output 3 - * @param adc4 ADC output 4 - * @param adc5 ADC output 5 - * @param adc6 ADC output 6 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AP_ADC_LEN]; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, adc5); - _mav_put_uint16_t(buf, 10, adc6); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AP_ADC_LEN); -#else - mavlink_ap_adc_t packet; - packet.adc1 = adc1; - packet.adc2 = adc2; - packet.adc3 = adc3; - packet.adc4 = adc4; - packet.adc5 = adc5; - packet.adc6 = adc6; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AP_ADC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AP_ADC; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AP_ADC_LEN); -#endif -} - -/** - * @brief Encode a ap_adc struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ap_adc C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc) -{ - return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6); -} - -/** - * @brief Encode a ap_adc struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ap_adc C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ap_adc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc) -{ - return mavlink_msg_ap_adc_pack_chan(system_id, component_id, chan, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6); -} - -/** - * @brief Send a ap_adc message - * @param chan MAVLink channel to send the message - * - * @param adc1 ADC output 1 - * @param adc2 ADC output 2 - * @param adc3 ADC output 3 - * @param adc4 ADC output 4 - * @param adc5 ADC output 5 - * @param adc6 ADC output 6 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AP_ADC_LEN]; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, adc5); - _mav_put_uint16_t(buf, 10, adc6); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_LEN); -#endif -#else - mavlink_ap_adc_t packet; - packet.adc1 = adc1; - packet.adc2 = adc2; - packet.adc3 = adc3; - packet.adc4 = adc4; - packet.adc5 = adc5; - packet.adc6 = adc6; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, MAVLINK_MSG_ID_AP_ADC_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_AP_ADC_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_ap_adc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, adc1); - _mav_put_uint16_t(buf, 2, adc2); - _mav_put_uint16_t(buf, 4, adc3); - _mav_put_uint16_t(buf, 6, adc4); - _mav_put_uint16_t(buf, 8, adc5); - _mav_put_uint16_t(buf, 10, adc6); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_LEN); -#endif -#else - mavlink_ap_adc_t *packet = (mavlink_ap_adc_t *)msgbuf; - packet->adc1 = adc1; - packet->adc2 = adc2; - packet->adc3 = adc3; - packet->adc4 = adc4; - packet->adc5 = adc5; - packet->adc6 = adc6; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)packet, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)packet, MAVLINK_MSG_ID_AP_ADC_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE AP_ADC UNPACKING - - -/** - * @brief Get field adc1 from ap_adc message - * - * @return ADC output 1 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field adc2 from ap_adc message - * - * @return ADC output 2 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field adc3 from ap_adc message - * - * @return ADC output 3 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field adc4 from ap_adc message - * - * @return ADC output 4 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field adc5 from ap_adc message - * - * @return ADC output 5 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field adc6 from ap_adc message - * - * @return ADC output 6 - */ -static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Decode a ap_adc message into a struct - * - * @param msg The message to decode - * @param ap_adc C-struct to decode the message contents into - */ -static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc) -{ -#if MAVLINK_NEED_BYTE_SWAP - ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg); - ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg); - ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg); - ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg); - ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg); - ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg); -#else - memcpy(ap_adc, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AP_ADC_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_compassmot_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_compassmot_status.h deleted file mode 100644 index 965545988..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_compassmot_status.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE COMPASSMOT_STATUS PACKING - -#define MAVLINK_MSG_ID_COMPASSMOT_STATUS 177 - -typedef struct __mavlink_compassmot_status_t -{ - float current; ///< current (amps) - float CompensationX; ///< Motor Compensation X - float CompensationY; ///< Motor Compensation Y - float CompensationZ; ///< Motor Compensation Z - uint16_t throttle; ///< throttle (percent*10) - uint16_t interference; ///< interference (percent) -} mavlink_compassmot_status_t; - -#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN 20 -#define MAVLINK_MSG_ID_177_LEN 20 - -#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC 240 -#define MAVLINK_MSG_ID_177_CRC 240 - - - -#define MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS { \ - "COMPASSMOT_STATUS", \ - 6, \ - { { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_compassmot_status_t, current) }, \ - { "CompensationX", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_compassmot_status_t, CompensationX) }, \ - { "CompensationY", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_compassmot_status_t, CompensationY) }, \ - { "CompensationZ", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_compassmot_status_t, CompensationZ) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_compassmot_status_t, throttle) }, \ - { "interference", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_compassmot_status_t, interference) }, \ - } \ -} - - -/** - * @brief Pack a compassmot_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param throttle throttle (percent*10) - * @param current current (amps) - * @param interference interference (percent) - * @param CompensationX Motor Compensation X - * @param CompensationY Motor Compensation Y - * @param CompensationZ Motor Compensation Z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_compassmot_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN]; - _mav_put_float(buf, 0, current); - _mav_put_float(buf, 4, CompensationX); - _mav_put_float(buf, 8, CompensationY); - _mav_put_float(buf, 12, CompensationZ); - _mav_put_uint16_t(buf, 16, throttle); - _mav_put_uint16_t(buf, 18, interference); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#else - mavlink_compassmot_status_t packet; - packet.current = current; - packet.CompensationX = CompensationX; - packet.CompensationY = CompensationY; - packet.CompensationZ = CompensationZ; - packet.throttle = throttle; - packet.interference = interference; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#endif -} - -/** - * @brief Pack a compassmot_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param throttle throttle (percent*10) - * @param current current (amps) - * @param interference interference (percent) - * @param CompensationX Motor Compensation X - * @param CompensationY Motor Compensation Y - * @param CompensationZ Motor Compensation Z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_compassmot_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t throttle,float current,uint16_t interference,float CompensationX,float CompensationY,float CompensationZ) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN]; - _mav_put_float(buf, 0, current); - _mav_put_float(buf, 4, CompensationX); - _mav_put_float(buf, 8, CompensationY); - _mav_put_float(buf, 12, CompensationZ); - _mav_put_uint16_t(buf, 16, throttle); - _mav_put_uint16_t(buf, 18, interference); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#else - mavlink_compassmot_status_t packet; - packet.current = current; - packet.CompensationX = CompensationX; - packet.CompensationY = CompensationY; - packet.CompensationZ = CompensationZ; - packet.throttle = throttle; - packet.interference = interference; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#endif -} - -/** - * @brief Encode a compassmot_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param compassmot_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_compassmot_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status) -{ - return mavlink_msg_compassmot_status_pack(system_id, component_id, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ); -} - -/** - * @brief Encode a compassmot_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param compassmot_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_compassmot_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status) -{ - return mavlink_msg_compassmot_status_pack_chan(system_id, component_id, chan, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ); -} - -/** - * @brief Send a compassmot_status message - * @param chan MAVLink channel to send the message - * - * @param throttle throttle (percent*10) - * @param current current (amps) - * @param interference interference (percent) - * @param CompensationX Motor Compensation X - * @param CompensationY Motor Compensation Y - * @param CompensationZ Motor Compensation Z - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_compassmot_status_send(mavlink_channel_t chan, uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN]; - _mav_put_float(buf, 0, current); - _mav_put_float(buf, 4, CompensationX); - _mav_put_float(buf, 8, CompensationY); - _mav_put_float(buf, 12, CompensationZ); - _mav_put_uint16_t(buf, 16, throttle); - _mav_put_uint16_t(buf, 18, interference); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#endif -#else - mavlink_compassmot_status_t packet; - packet.current = current; - packet.CompensationX = CompensationX; - packet.CompensationY = CompensationY; - packet.CompensationZ = CompensationZ; - packet.throttle = throttle; - packet.interference = interference; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_compassmot_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, current); - _mav_put_float(buf, 4, CompensationX); - _mav_put_float(buf, 8, CompensationY); - _mav_put_float(buf, 12, CompensationZ); - _mav_put_uint16_t(buf, 16, throttle); - _mav_put_uint16_t(buf, 18, interference); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#endif -#else - mavlink_compassmot_status_t *packet = (mavlink_compassmot_status_t *)msgbuf; - packet->current = current; - packet->CompensationX = CompensationX; - packet->CompensationY = CompensationY; - packet->CompensationZ = CompensationZ; - packet->throttle = throttle; - packet->interference = interference; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE COMPASSMOT_STATUS UNPACKING - - -/** - * @brief Get field throttle from compassmot_status message - * - * @return throttle (percent*10) - */ -static inline uint16_t mavlink_msg_compassmot_status_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field current from compassmot_status message - * - * @return current (amps) - */ -static inline float mavlink_msg_compassmot_status_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field interference from compassmot_status message - * - * @return interference (percent) - */ -static inline uint16_t mavlink_msg_compassmot_status_get_interference(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field CompensationX from compassmot_status message - * - * @return Motor Compensation X - */ -static inline float mavlink_msg_compassmot_status_get_CompensationX(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field CompensationY from compassmot_status message - * - * @return Motor Compensation Y - */ -static inline float mavlink_msg_compassmot_status_get_CompensationY(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field CompensationZ from compassmot_status message - * - * @return Motor Compensation Z - */ -static inline float mavlink_msg_compassmot_status_get_CompensationZ(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a compassmot_status message into a struct - * - * @param msg The message to decode - * @param compassmot_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_compassmot_status_decode(const mavlink_message_t* msg, mavlink_compassmot_status_t* compassmot_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - compassmot_status->current = mavlink_msg_compassmot_status_get_current(msg); - compassmot_status->CompensationX = mavlink_msg_compassmot_status_get_CompensationX(msg); - compassmot_status->CompensationY = mavlink_msg_compassmot_status_get_CompensationY(msg); - compassmot_status->CompensationZ = mavlink_msg_compassmot_status_get_CompensationZ(msg); - compassmot_status->throttle = mavlink_msg_compassmot_status_get_throttle(msg); - compassmot_status->interference = mavlink_msg_compassmot_status_get_interference(msg); -#else - memcpy(compassmot_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h deleted file mode 100644 index 7bad1b23d..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data16.h +++ /dev/null @@ -1,249 +0,0 @@ -// MESSAGE DATA16 PACKING - -#define MAVLINK_MSG_ID_DATA16 169 - -typedef struct __mavlink_data16_t -{ - uint8_t type; ///< data type - uint8_t len; ///< data length - uint8_t data[16]; ///< raw data -} mavlink_data16_t; - -#define MAVLINK_MSG_ID_DATA16_LEN 18 -#define MAVLINK_MSG_ID_169_LEN 18 - -#define MAVLINK_MSG_ID_DATA16_CRC 234 -#define MAVLINK_MSG_ID_169_CRC 234 - -#define MAVLINK_MSG_DATA16_FIELD_DATA_LEN 16 - -#define MAVLINK_MESSAGE_INFO_DATA16 { \ - "DATA16", \ - 3, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data16_t, type) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data16_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 16, 2, offsetof(mavlink_data16_t, data) }, \ - } \ -} - - -/** - * @brief Pack a data16 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type data type - * @param len data length - * @param data raw data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data16_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA16_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA16_LEN); -#else - mavlink_data16_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA16_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA16; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA16_LEN); -#endif -} - -/** - * @brief Pack a data16 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type data type - * @param len data length - * @param data raw data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data16_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA16_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA16_LEN); -#else - mavlink_data16_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA16_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA16; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA16_LEN); -#endif -} - -/** - * @brief Encode a data16 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data16 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data16_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data16_t* data16) -{ - return mavlink_msg_data16_pack(system_id, component_id, msg, data16->type, data16->len, data16->data); -} - -/** - * @brief Encode a data16 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data16 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data16_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data16_t* data16) -{ - return mavlink_msg_data16_pack_chan(system_id, component_id, chan, msg, data16->type, data16->len, data16->data); -} - -/** - * @brief Send a data16 message - * @param chan MAVLink channel to send the message - * - * @param type data type - * @param len data length - * @param data raw data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_data16_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA16_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_LEN); -#endif -#else - mavlink_data16_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)&packet, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)&packet, MAVLINK_MSG_ID_DATA16_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DATA16_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data16_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_LEN); -#endif -#else - mavlink_data16_t *packet = (mavlink_data16_t *)msgbuf; - packet->type = type; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)packet, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)packet, MAVLINK_MSG_ID_DATA16_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DATA16 UNPACKING - - -/** - * @brief Get field type from data16 message - * - * @return data type - */ -static inline uint8_t mavlink_msg_data16_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field len from data16 message - * - * @return data length - */ -static inline uint8_t mavlink_msg_data16_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field data from data16 message - * - * @return raw data - */ -static inline uint16_t mavlink_msg_data16_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 16, 2); -} - -/** - * @brief Decode a data16 message into a struct - * - * @param msg The message to decode - * @param data16 C-struct to decode the message contents into - */ -static inline void mavlink_msg_data16_decode(const mavlink_message_t* msg, mavlink_data16_t* data16) -{ -#if MAVLINK_NEED_BYTE_SWAP - data16->type = mavlink_msg_data16_get_type(msg); - data16->len = mavlink_msg_data16_get_len(msg); - mavlink_msg_data16_get_data(msg, data16->data); -#else - memcpy(data16, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA16_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h deleted file mode 100644 index df7a2ec80..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data32.h +++ /dev/null @@ -1,249 +0,0 @@ -// MESSAGE DATA32 PACKING - -#define MAVLINK_MSG_ID_DATA32 170 - -typedef struct __mavlink_data32_t -{ - uint8_t type; ///< data type - uint8_t len; ///< data length - uint8_t data[32]; ///< raw data -} mavlink_data32_t; - -#define MAVLINK_MSG_ID_DATA32_LEN 34 -#define MAVLINK_MSG_ID_170_LEN 34 - -#define MAVLINK_MSG_ID_DATA32_CRC 73 -#define MAVLINK_MSG_ID_170_CRC 73 - -#define MAVLINK_MSG_DATA32_FIELD_DATA_LEN 32 - -#define MAVLINK_MESSAGE_INFO_DATA32 { \ - "DATA32", \ - 3, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data32_t, type) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data32_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 32, 2, offsetof(mavlink_data32_t, data) }, \ - } \ -} - - -/** - * @brief Pack a data32 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type data type - * @param len data length - * @param data raw data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data32_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA32_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA32_LEN); -#else - mavlink_data32_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA32_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA32; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA32_LEN); -#endif -} - -/** - * @brief Pack a data32 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type data type - * @param len data length - * @param data raw data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data32_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA32_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA32_LEN); -#else - mavlink_data32_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA32_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA32; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA32_LEN); -#endif -} - -/** - * @brief Encode a data32 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data32 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data32_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data32_t* data32) -{ - return mavlink_msg_data32_pack(system_id, component_id, msg, data32->type, data32->len, data32->data); -} - -/** - * @brief Encode a data32 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data32 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data32_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data32_t* data32) -{ - return mavlink_msg_data32_pack_chan(system_id, component_id, chan, msg, data32->type, data32->len, data32->data); -} - -/** - * @brief Send a data32 message - * @param chan MAVLink channel to send the message - * - * @param type data type - * @param len data length - * @param data raw data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_data32_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA32_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_LEN); -#endif -#else - mavlink_data32_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)&packet, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)&packet, MAVLINK_MSG_ID_DATA32_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DATA32_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data32_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_LEN); -#endif -#else - mavlink_data32_t *packet = (mavlink_data32_t *)msgbuf; - packet->type = type; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)packet, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)packet, MAVLINK_MSG_ID_DATA32_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DATA32 UNPACKING - - -/** - * @brief Get field type from data32 message - * - * @return data type - */ -static inline uint8_t mavlink_msg_data32_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field len from data32 message - * - * @return data length - */ -static inline uint8_t mavlink_msg_data32_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field data from data32 message - * - * @return raw data - */ -static inline uint16_t mavlink_msg_data32_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 32, 2); -} - -/** - * @brief Decode a data32 message into a struct - * - * @param msg The message to decode - * @param data32 C-struct to decode the message contents into - */ -static inline void mavlink_msg_data32_decode(const mavlink_message_t* msg, mavlink_data32_t* data32) -{ -#if MAVLINK_NEED_BYTE_SWAP - data32->type = mavlink_msg_data32_get_type(msg); - data32->len = mavlink_msg_data32_get_len(msg); - mavlink_msg_data32_get_data(msg, data32->data); -#else - memcpy(data32, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA32_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h deleted file mode 100644 index c354f8908..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data64.h +++ /dev/null @@ -1,249 +0,0 @@ -// MESSAGE DATA64 PACKING - -#define MAVLINK_MSG_ID_DATA64 171 - -typedef struct __mavlink_data64_t -{ - uint8_t type; ///< data type - uint8_t len; ///< data length - uint8_t data[64]; ///< raw data -} mavlink_data64_t; - -#define MAVLINK_MSG_ID_DATA64_LEN 66 -#define MAVLINK_MSG_ID_171_LEN 66 - -#define MAVLINK_MSG_ID_DATA64_CRC 181 -#define MAVLINK_MSG_ID_171_CRC 181 - -#define MAVLINK_MSG_DATA64_FIELD_DATA_LEN 64 - -#define MAVLINK_MESSAGE_INFO_DATA64 { \ - "DATA64", \ - 3, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data64_t, type) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data64_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 64, 2, offsetof(mavlink_data64_t, data) }, \ - } \ -} - - -/** - * @brief Pack a data64 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type data type - * @param len data length - * @param data raw data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data64_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA64_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA64_LEN); -#else - mavlink_data64_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA64_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA64; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA64_LEN); -#endif -} - -/** - * @brief Pack a data64 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type data type - * @param len data length - * @param data raw data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data64_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA64_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA64_LEN); -#else - mavlink_data64_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA64_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA64; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA64_LEN); -#endif -} - -/** - * @brief Encode a data64 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data64 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data64_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data64_t* data64) -{ - return mavlink_msg_data64_pack(system_id, component_id, msg, data64->type, data64->len, data64->data); -} - -/** - * @brief Encode a data64 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data64 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data64_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data64_t* data64) -{ - return mavlink_msg_data64_pack_chan(system_id, component_id, chan, msg, data64->type, data64->len, data64->data); -} - -/** - * @brief Send a data64 message - * @param chan MAVLink channel to send the message - * - * @param type data type - * @param len data length - * @param data raw data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_data64_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA64_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 64); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_LEN); -#endif -#else - mavlink_data64_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)&packet, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)&packet, MAVLINK_MSG_ID_DATA64_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DATA64_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data64_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 64); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_LEN); -#endif -#else - mavlink_data64_t *packet = (mavlink_data64_t *)msgbuf; - packet->type = type; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*64); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)packet, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)packet, MAVLINK_MSG_ID_DATA64_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DATA64 UNPACKING - - -/** - * @brief Get field type from data64 message - * - * @return data type - */ -static inline uint8_t mavlink_msg_data64_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field len from data64 message - * - * @return data length - */ -static inline uint8_t mavlink_msg_data64_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field data from data64 message - * - * @return raw data - */ -static inline uint16_t mavlink_msg_data64_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 64, 2); -} - -/** - * @brief Decode a data64 message into a struct - * - * @param msg The message to decode - * @param data64 C-struct to decode the message contents into - */ -static inline void mavlink_msg_data64_decode(const mavlink_message_t* msg, mavlink_data64_t* data64) -{ -#if MAVLINK_NEED_BYTE_SWAP - data64->type = mavlink_msg_data64_get_type(msg); - data64->len = mavlink_msg_data64_get_len(msg); - mavlink_msg_data64_get_data(msg, data64->data); -#else - memcpy(data64, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA64_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h deleted file mode 100644 index 634e3f81d..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_data96.h +++ /dev/null @@ -1,249 +0,0 @@ -// MESSAGE DATA96 PACKING - -#define MAVLINK_MSG_ID_DATA96 172 - -typedef struct __mavlink_data96_t -{ - uint8_t type; ///< data type - uint8_t len; ///< data length - uint8_t data[96]; ///< raw data -} mavlink_data96_t; - -#define MAVLINK_MSG_ID_DATA96_LEN 98 -#define MAVLINK_MSG_ID_172_LEN 98 - -#define MAVLINK_MSG_ID_DATA96_CRC 22 -#define MAVLINK_MSG_ID_172_CRC 22 - -#define MAVLINK_MSG_DATA96_FIELD_DATA_LEN 96 - -#define MAVLINK_MESSAGE_INFO_DATA96 { \ - "DATA96", \ - 3, \ - { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data96_t, type) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data96_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 96, 2, offsetof(mavlink_data96_t, data) }, \ - } \ -} - - -/** - * @brief Pack a data96 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type data type - * @param len data length - * @param data raw data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data96_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA96_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 96); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA96_LEN); -#else - mavlink_data96_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA96_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA96; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA96_LEN); -#endif -} - -/** - * @brief Pack a data96 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type data type - * @param len data length - * @param data raw data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data96_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA96_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 96); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA96_LEN); -#else - mavlink_data96_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA96_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA96; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA96_LEN); -#endif -} - -/** - * @brief Encode a data96 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data96 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data96_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data96_t* data96) -{ - return mavlink_msg_data96_pack(system_id, component_id, msg, data96->type, data96->len, data96->data); -} - -/** - * @brief Encode a data96 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data96 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data96_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data96_t* data96) -{ - return mavlink_msg_data96_pack_chan(system_id, component_id, chan, msg, data96->type, data96->len, data96->data); -} - -/** - * @brief Send a data96 message - * @param chan MAVLink channel to send the message - * - * @param type data type - * @param len data length - * @param data raw data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_data96_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA96_LEN]; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 96); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_LEN); -#endif -#else - mavlink_data96_t packet; - packet.type = type; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)&packet, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)&packet, MAVLINK_MSG_ID_DATA96_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DATA96_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data96_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, type); - _mav_put_uint8_t(buf, 1, len); - _mav_put_uint8_t_array(buf, 2, data, 96); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_LEN); -#endif -#else - mavlink_data96_t *packet = (mavlink_data96_t *)msgbuf; - packet->type = type; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*96); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)packet, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)packet, MAVLINK_MSG_ID_DATA96_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DATA96 UNPACKING - - -/** - * @brief Get field type from data96 message - * - * @return data type - */ -static inline uint8_t mavlink_msg_data96_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field len from data96 message - * - * @return data length - */ -static inline uint8_t mavlink_msg_data96_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field data from data96 message - * - * @return raw data - */ -static inline uint16_t mavlink_msg_data96_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 96, 2); -} - -/** - * @brief Decode a data96 message into a struct - * - * @param msg The message to decode - * @param data96 C-struct to decode the message contents into - */ -static inline void mavlink_msg_data96_decode(const mavlink_message_t* msg, mavlink_data96_t* data96) -{ -#if MAVLINK_NEED_BYTE_SWAP - data96->type = mavlink_msg_data96_get_type(msg); - data96->len = mavlink_msg_data96_get_len(msg); - mavlink_msg_data96_get_data(msg, data96->data); -#else - memcpy(data96, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA96_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h deleted file mode 100644 index d5f9e7132..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h +++ /dev/null @@ -1,449 +0,0 @@ -// MESSAGE DIGICAM_CONFIGURE PACKING - -#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE 154 - -typedef struct __mavlink_digicam_configure_t -{ - float extra_value; ///< Correspondent value to given extra_param - uint16_t shutter_speed; ///< Divisor number //e.g. 1000 means 1/1000 (0 means ignore) - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t mode; ///< Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) - uint8_t aperture; ///< F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) - uint8_t iso; ///< ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) - uint8_t exposure_type; ///< Exposure type enumeration from 1 to N (0 means ignore) - uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - uint8_t engine_cut_off; ///< Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) - uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore) -} mavlink_digicam_configure_t; - -#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN 15 -#define MAVLINK_MSG_ID_154_LEN 15 - -#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC 84 -#define MAVLINK_MSG_ID_154_CRC 84 - - - -#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \ - "DIGICAM_CONFIGURE", \ - 11, \ - { { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_configure_t, extra_value) }, \ - { "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, target_component) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, mode) }, \ - { "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, aperture) }, \ - { "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, iso) }, \ - { "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_configure_t, exposure_type) }, \ - { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_configure_t, command_id) }, \ - { "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \ - { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_digicam_configure_t, extra_param) }, \ - } \ -} - - -/** - * @brief Pack a digicam_configure message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) - * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore) - * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) - * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) - * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore) - * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - * @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) - * @param extra_param Extra parameters enumeration (0 means ignore) - * @param extra_value Correspondent value to given extra_param - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN]; - _mav_put_float(buf, 0, extra_value); - _mav_put_uint16_t(buf, 4, shutter_speed); - _mav_put_uint8_t(buf, 6, target_system); - _mav_put_uint8_t(buf, 7, target_component); - _mav_put_uint8_t(buf, 8, mode); - _mav_put_uint8_t(buf, 9, aperture); - _mav_put_uint8_t(buf, 10, iso); - _mav_put_uint8_t(buf, 11, exposure_type); - _mav_put_uint8_t(buf, 12, command_id); - _mav_put_uint8_t(buf, 13, engine_cut_off); - _mav_put_uint8_t(buf, 14, extra_param); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#else - mavlink_digicam_configure_t packet; - packet.extra_value = extra_value; - packet.shutter_speed = shutter_speed; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mode = mode; - packet.aperture = aperture; - packet.iso = iso; - packet.exposure_type = exposure_type; - packet.command_id = command_id; - packet.engine_cut_off = engine_cut_off; - packet.extra_param = extra_param; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#endif -} - -/** - * @brief Pack a digicam_configure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) - * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore) - * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) - * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) - * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore) - * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - * @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) - * @param extra_param Extra parameters enumeration (0 means ignore) - * @param extra_value Correspondent value to given extra_param - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t mode,uint16_t shutter_speed,uint8_t aperture,uint8_t iso,uint8_t exposure_type,uint8_t command_id,uint8_t engine_cut_off,uint8_t extra_param,float extra_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN]; - _mav_put_float(buf, 0, extra_value); - _mav_put_uint16_t(buf, 4, shutter_speed); - _mav_put_uint8_t(buf, 6, target_system); - _mav_put_uint8_t(buf, 7, target_component); - _mav_put_uint8_t(buf, 8, mode); - _mav_put_uint8_t(buf, 9, aperture); - _mav_put_uint8_t(buf, 10, iso); - _mav_put_uint8_t(buf, 11, exposure_type); - _mav_put_uint8_t(buf, 12, command_id); - _mav_put_uint8_t(buf, 13, engine_cut_off); - _mav_put_uint8_t(buf, 14, extra_param); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#else - mavlink_digicam_configure_t packet; - packet.extra_value = extra_value; - packet.shutter_speed = shutter_speed; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mode = mode; - packet.aperture = aperture; - packet.iso = iso; - packet.exposure_type = exposure_type; - packet.command_id = command_id; - packet.engine_cut_off = engine_cut_off; - packet.extra_param = extra_param; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#endif -} - -/** - * @brief Encode a digicam_configure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param digicam_configure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure) -{ - return mavlink_msg_digicam_configure_pack(system_id, component_id, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value); -} - -/** - * @brief Encode a digicam_configure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param digicam_configure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_digicam_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure) -{ - return mavlink_msg_digicam_configure_pack_chan(system_id, component_id, chan, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value); -} - -/** - * @brief Send a digicam_configure message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) - * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore) - * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) - * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) - * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore) - * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - * @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) - * @param extra_param Extra parameters enumeration (0 means ignore) - * @param extra_value Correspondent value to given extra_param - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN]; - _mav_put_float(buf, 0, extra_value); - _mav_put_uint16_t(buf, 4, shutter_speed); - _mav_put_uint8_t(buf, 6, target_system); - _mav_put_uint8_t(buf, 7, target_component); - _mav_put_uint8_t(buf, 8, mode); - _mav_put_uint8_t(buf, 9, aperture); - _mav_put_uint8_t(buf, 10, iso); - _mav_put_uint8_t(buf, 11, exposure_type); - _mav_put_uint8_t(buf, 12, command_id); - _mav_put_uint8_t(buf, 13, engine_cut_off); - _mav_put_uint8_t(buf, 14, extra_param); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#endif -#else - mavlink_digicam_configure_t packet; - packet.extra_value = extra_value; - packet.shutter_speed = shutter_speed; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mode = mode; - packet.aperture = aperture; - packet.iso = iso; - packet.exposure_type = exposure_type; - packet.command_id = command_id; - packet.engine_cut_off = engine_cut_off; - packet.extra_param = extra_param; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_digicam_configure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, extra_value); - _mav_put_uint16_t(buf, 4, shutter_speed); - _mav_put_uint8_t(buf, 6, target_system); - _mav_put_uint8_t(buf, 7, target_component); - _mav_put_uint8_t(buf, 8, mode); - _mav_put_uint8_t(buf, 9, aperture); - _mav_put_uint8_t(buf, 10, iso); - _mav_put_uint8_t(buf, 11, exposure_type); - _mav_put_uint8_t(buf, 12, command_id); - _mav_put_uint8_t(buf, 13, engine_cut_off); - _mav_put_uint8_t(buf, 14, extra_param); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#endif -#else - mavlink_digicam_configure_t *packet = (mavlink_digicam_configure_t *)msgbuf; - packet->extra_value = extra_value; - packet->shutter_speed = shutter_speed; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mode = mode; - packet->aperture = aperture; - packet->iso = iso; - packet->exposure_type = exposure_type; - packet->command_id = command_id; - packet->engine_cut_off = engine_cut_off; - packet->extra_param = extra_param; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DIGICAM_CONFIGURE UNPACKING - - -/** - * @brief Get field target_system from digicam_configure message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_digicam_configure_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field target_component from digicam_configure message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_digicam_configure_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field mode from digicam_configure message - * - * @return Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore) - */ -static inline uint8_t mavlink_msg_digicam_configure_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field shutter_speed from digicam_configure message - * - * @return Divisor number //e.g. 1000 means 1/1000 (0 means ignore) - */ -static inline uint16_t mavlink_msg_digicam_configure_get_shutter_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field aperture from digicam_configure message - * - * @return F stop number x 10 //e.g. 28 means 2.8 (0 means ignore) - */ -static inline uint8_t mavlink_msg_digicam_configure_get_aperture(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Get field iso from digicam_configure message - * - * @return ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore) - */ -static inline uint8_t mavlink_msg_digicam_configure_get_iso(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field exposure_type from digicam_configure message - * - * @return Exposure type enumeration from 1 to N (0 means ignore) - */ -static inline uint8_t mavlink_msg_digicam_configure_get_exposure_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field command_id from digicam_configure message - * - * @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - */ -static inline uint8_t mavlink_msg_digicam_configure_get_command_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field engine_cut_off from digicam_configure message - * - * @return Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off) - */ -static inline uint8_t mavlink_msg_digicam_configure_get_engine_cut_off(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Get field extra_param from digicam_configure message - * - * @return Extra parameters enumeration (0 means ignore) - */ -static inline uint8_t mavlink_msg_digicam_configure_get_extra_param(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Get field extra_value from digicam_configure message - * - * @return Correspondent value to given extra_param - */ -static inline float mavlink_msg_digicam_configure_get_extra_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Decode a digicam_configure message into a struct - * - * @param msg The message to decode - * @param digicam_configure C-struct to decode the message contents into - */ -static inline void mavlink_msg_digicam_configure_decode(const mavlink_message_t* msg, mavlink_digicam_configure_t* digicam_configure) -{ -#if MAVLINK_NEED_BYTE_SWAP - digicam_configure->extra_value = mavlink_msg_digicam_configure_get_extra_value(msg); - digicam_configure->shutter_speed = mavlink_msg_digicam_configure_get_shutter_speed(msg); - digicam_configure->target_system = mavlink_msg_digicam_configure_get_target_system(msg); - digicam_configure->target_component = mavlink_msg_digicam_configure_get_target_component(msg); - digicam_configure->mode = mavlink_msg_digicam_configure_get_mode(msg); - digicam_configure->aperture = mavlink_msg_digicam_configure_get_aperture(msg); - digicam_configure->iso = mavlink_msg_digicam_configure_get_iso(msg); - digicam_configure->exposure_type = mavlink_msg_digicam_configure_get_exposure_type(msg); - digicam_configure->command_id = mavlink_msg_digicam_configure_get_command_id(msg); - digicam_configure->engine_cut_off = mavlink_msg_digicam_configure_get_engine_cut_off(msg); - digicam_configure->extra_param = mavlink_msg_digicam_configure_get_extra_param(msg); -#else - memcpy(digicam_configure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h deleted file mode 100644 index 68484f7b8..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h +++ /dev/null @@ -1,425 +0,0 @@ -// MESSAGE DIGICAM_CONTROL PACKING - -#define MAVLINK_MSG_ID_DIGICAM_CONTROL 155 - -typedef struct __mavlink_digicam_control_t -{ - float extra_value; ///< Correspondent value to given extra_param - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t session; ///< 0: stop, 1: start or keep it up //Session control e.g. show/hide lens - uint8_t zoom_pos; ///< 1 to N //Zoom's absolute position (0 means ignore) - int8_t zoom_step; ///< -100 to 100 //Zooming step value to offset zoom from the current position - uint8_t focus_lock; ///< 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus - uint8_t shot; ///< 0: ignore, 1: shot or start filming - uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore) -} mavlink_digicam_control_t; - -#define MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN 13 -#define MAVLINK_MSG_ID_155_LEN 13 - -#define MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC 22 -#define MAVLINK_MSG_ID_155_CRC 22 - - - -#define MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL { \ - "DIGICAM_CONTROL", \ - 10, \ - { { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_control_t, extra_value) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_digicam_control_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_digicam_control_t, target_component) }, \ - { "session", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_control_t, session) }, \ - { "zoom_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_control_t, zoom_pos) }, \ - { "zoom_step", NULL, MAVLINK_TYPE_INT8_T, 0, 8, offsetof(mavlink_digicam_control_t, zoom_step) }, \ - { "focus_lock", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_control_t, focus_lock) }, \ - { "shot", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_control_t, shot) }, \ - { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_control_t, command_id) }, \ - { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_control_t, extra_param) }, \ - } \ -} - - -/** - * @brief Pack a digicam_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens - * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore) - * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position - * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus - * @param shot 0: ignore, 1: shot or start filming - * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - * @param extra_param Extra parameters enumeration (0 means ignore) - * @param extra_value Correspondent value to given extra_param - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN]; - _mav_put_float(buf, 0, extra_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, session); - _mav_put_uint8_t(buf, 7, zoom_pos); - _mav_put_int8_t(buf, 8, zoom_step); - _mav_put_uint8_t(buf, 9, focus_lock); - _mav_put_uint8_t(buf, 10, shot); - _mav_put_uint8_t(buf, 11, command_id); - _mav_put_uint8_t(buf, 12, extra_param); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#else - mavlink_digicam_control_t packet; - packet.extra_value = extra_value; - packet.target_system = target_system; - packet.target_component = target_component; - packet.session = session; - packet.zoom_pos = zoom_pos; - packet.zoom_step = zoom_step; - packet.focus_lock = focus_lock; - packet.shot = shot; - packet.command_id = command_id; - packet.extra_param = extra_param; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#endif -} - -/** - * @brief Pack a digicam_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens - * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore) - * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position - * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus - * @param shot 0: ignore, 1: shot or start filming - * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - * @param extra_param Extra parameters enumeration (0 means ignore) - * @param extra_value Correspondent value to given extra_param - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t session,uint8_t zoom_pos,int8_t zoom_step,uint8_t focus_lock,uint8_t shot,uint8_t command_id,uint8_t extra_param,float extra_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN]; - _mav_put_float(buf, 0, extra_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, session); - _mav_put_uint8_t(buf, 7, zoom_pos); - _mav_put_int8_t(buf, 8, zoom_step); - _mav_put_uint8_t(buf, 9, focus_lock); - _mav_put_uint8_t(buf, 10, shot); - _mav_put_uint8_t(buf, 11, command_id); - _mav_put_uint8_t(buf, 12, extra_param); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#else - mavlink_digicam_control_t packet; - packet.extra_value = extra_value; - packet.target_system = target_system; - packet.target_component = target_component; - packet.session = session; - packet.zoom_pos = zoom_pos; - packet.zoom_step = zoom_step; - packet.focus_lock = focus_lock; - packet.shot = shot; - packet.command_id = command_id; - packet.extra_param = extra_param; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#endif -} - -/** - * @brief Encode a digicam_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param digicam_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_digicam_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control) -{ - return mavlink_msg_digicam_control_pack(system_id, component_id, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value); -} - -/** - * @brief Encode a digicam_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param digicam_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_digicam_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control) -{ - return mavlink_msg_digicam_control_pack_chan(system_id, component_id, chan, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value); -} - -/** - * @brief Send a digicam_control message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens - * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore) - * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position - * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus - * @param shot 0: ignore, 1: shot or start filming - * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - * @param extra_param Extra parameters enumeration (0 means ignore) - * @param extra_value Correspondent value to given extra_param - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN]; - _mav_put_float(buf, 0, extra_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, session); - _mav_put_uint8_t(buf, 7, zoom_pos); - _mav_put_int8_t(buf, 8, zoom_step); - _mav_put_uint8_t(buf, 9, focus_lock); - _mav_put_uint8_t(buf, 10, shot); - _mav_put_uint8_t(buf, 11, command_id); - _mav_put_uint8_t(buf, 12, extra_param); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#endif -#else - mavlink_digicam_control_t packet; - packet.extra_value = extra_value; - packet.target_system = target_system; - packet.target_component = target_component; - packet.session = session; - packet.zoom_pos = zoom_pos; - packet.zoom_step = zoom_step; - packet.focus_lock = focus_lock; - packet.shot = shot; - packet.command_id = command_id; - packet.extra_param = extra_param; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_digicam_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, extra_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 6, session); - _mav_put_uint8_t(buf, 7, zoom_pos); - _mav_put_int8_t(buf, 8, zoom_step); - _mav_put_uint8_t(buf, 9, focus_lock); - _mav_put_uint8_t(buf, 10, shot); - _mav_put_uint8_t(buf, 11, command_id); - _mav_put_uint8_t(buf, 12, extra_param); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#endif -#else - mavlink_digicam_control_t *packet = (mavlink_digicam_control_t *)msgbuf; - packet->extra_value = extra_value; - packet->target_system = target_system; - packet->target_component = target_component; - packet->session = session; - packet->zoom_pos = zoom_pos; - packet->zoom_step = zoom_step; - packet->focus_lock = focus_lock; - packet->shot = shot; - packet->command_id = command_id; - packet->extra_param = extra_param; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DIGICAM_CONTROL UNPACKING - - -/** - * @brief Get field target_system from digicam_control message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_digicam_control_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from digicam_control message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_digicam_control_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field session from digicam_control message - * - * @return 0: stop, 1: start or keep it up //Session control e.g. show/hide lens - */ -static inline uint8_t mavlink_msg_digicam_control_get_session(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field zoom_pos from digicam_control message - * - * @return 1 to N //Zoom's absolute position (0 means ignore) - */ -static inline uint8_t mavlink_msg_digicam_control_get_zoom_pos(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field zoom_step from digicam_control message - * - * @return -100 to 100 //Zooming step value to offset zoom from the current position - */ -static inline int8_t mavlink_msg_digicam_control_get_zoom_step(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 8); -} - -/** - * @brief Get field focus_lock from digicam_control message - * - * @return 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus - */ -static inline uint8_t mavlink_msg_digicam_control_get_focus_lock(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Get field shot from digicam_control message - * - * @return 0: ignore, 1: shot or start filming - */ -static inline uint8_t mavlink_msg_digicam_control_get_shot(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field command_id from digicam_control message - * - * @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once - */ -static inline uint8_t mavlink_msg_digicam_control_get_command_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field extra_param from digicam_control message - * - * @return Extra parameters enumeration (0 means ignore) - */ -static inline uint8_t mavlink_msg_digicam_control_get_extra_param(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field extra_value from digicam_control message - * - * @return Correspondent value to given extra_param - */ -static inline float mavlink_msg_digicam_control_get_extra_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Decode a digicam_control message into a struct - * - * @param msg The message to decode - * @param digicam_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_digicam_control_decode(const mavlink_message_t* msg, mavlink_digicam_control_t* digicam_control) -{ -#if MAVLINK_NEED_BYTE_SWAP - digicam_control->extra_value = mavlink_msg_digicam_control_get_extra_value(msg); - digicam_control->target_system = mavlink_msg_digicam_control_get_target_system(msg); - digicam_control->target_component = mavlink_msg_digicam_control_get_target_component(msg); - digicam_control->session = mavlink_msg_digicam_control_get_session(msg); - digicam_control->zoom_pos = mavlink_msg_digicam_control_get_zoom_pos(msg); - digicam_control->zoom_step = mavlink_msg_digicam_control_get_zoom_step(msg); - digicam_control->focus_lock = mavlink_msg_digicam_control_get_focus_lock(msg); - digicam_control->shot = mavlink_msg_digicam_control_get_shot(msg); - digicam_control->command_id = mavlink_msg_digicam_control_get_command_id(msg); - digicam_control->extra_param = mavlink_msg_digicam_control_get_extra_param(msg); -#else - memcpy(digicam_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h deleted file mode 100644 index 4021c7a09..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE FENCE_FETCH_POINT PACKING - -#define MAVLINK_MSG_ID_FENCE_FETCH_POINT 161 - -typedef struct __mavlink_fence_fetch_point_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t idx; ///< point index (first point is 1, 0 is for return point) -} mavlink_fence_fetch_point_t; - -#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN 3 -#define MAVLINK_MSG_ID_161_LEN 3 - -#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC 68 -#define MAVLINK_MSG_ID_161_CRC 68 - - - -#define MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT { \ - "FENCE_FETCH_POINT", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_fetch_point_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_fence_fetch_point_t, target_component) }, \ - { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_fence_fetch_point_t, idx) }, \ - } \ -} - - -/** - * @brief Pack a fence_fetch_point message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 1, 0 is for return point) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t idx) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, idx); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#else - mavlink_fence_fetch_point_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#endif -} - -/** - * @brief Pack a fence_fetch_point message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 1, 0 is for return point) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_fence_fetch_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t idx) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, idx); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#else - mavlink_fence_fetch_point_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#endif -} - -/** - * @brief Encode a fence_fetch_point struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param fence_fetch_point C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_fence_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point) -{ - return mavlink_msg_fence_fetch_point_pack(system_id, component_id, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx); -} - -/** - * @brief Encode a fence_fetch_point struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param fence_fetch_point C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_fence_fetch_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point) -{ - return mavlink_msg_fence_fetch_point_pack_chan(system_id, component_id, chan, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx); -} - -/** - * @brief Send a fence_fetch_point message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 1, 0 is for return point) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_fence_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, idx); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#endif -#else - mavlink_fence_fetch_point_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_fence_fetch_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, idx); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#endif -#else - mavlink_fence_fetch_point_t *packet = (mavlink_fence_fetch_point_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->idx = idx; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FENCE_FETCH_POINT UNPACKING - - -/** - * @brief Get field target_system from fence_fetch_point message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_fence_fetch_point_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from fence_fetch_point message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_fence_fetch_point_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field idx from fence_fetch_point message - * - * @return point index (first point is 1, 0 is for return point) - */ -static inline uint8_t mavlink_msg_fence_fetch_point_get_idx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a fence_fetch_point message into a struct - * - * @param msg The message to decode - * @param fence_fetch_point C-struct to decode the message contents into - */ -static inline void mavlink_msg_fence_fetch_point_decode(const mavlink_message_t* msg, mavlink_fence_fetch_point_t* fence_fetch_point) -{ -#if MAVLINK_NEED_BYTE_SWAP - fence_fetch_point->target_system = mavlink_msg_fence_fetch_point_get_target_system(msg); - fence_fetch_point->target_component = mavlink_msg_fence_fetch_point_get_target_component(msg); - fence_fetch_point->idx = mavlink_msg_fence_fetch_point_get_idx(msg); -#else - memcpy(fence_fetch_point, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h deleted file mode 100644 index 6fc2c83fc..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE FENCE_POINT PACKING - -#define MAVLINK_MSG_ID_FENCE_POINT 160 - -typedef struct __mavlink_fence_point_t -{ - float lat; ///< Latitude of point - float lng; ///< Longitude of point - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t idx; ///< point index (first point is 1, 0 is for return point) - uint8_t count; ///< total number of points (for sanity checking) -} mavlink_fence_point_t; - -#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12 -#define MAVLINK_MSG_ID_160_LEN 12 - -#define MAVLINK_MSG_ID_FENCE_POINT_CRC 78 -#define MAVLINK_MSG_ID_160_CRC 78 - - - -#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \ - "FENCE_POINT", \ - 6, \ - { { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \ - { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \ - { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \ - } \ -} - - -/** - * @brief Pack a fence_point message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 1, 0 is for return point) - * @param count total number of points (for sanity checking) - * @param lat Latitude of point - * @param lng Longitude of point - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN]; - _mav_put_float(buf, 0, lat); - _mav_put_float(buf, 4, lng); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t(buf, 10, idx); - _mav_put_uint8_t(buf, 11, count); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#else - mavlink_fence_point_t packet; - packet.lat = lat; - packet.lng = lng; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - packet.count = count; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FENCE_POINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#endif -} - -/** - * @brief Pack a fence_point message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 1, 0 is for return point) - * @param count total number of points (for sanity checking) - * @param lat Latitude of point - * @param lng Longitude of point - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t idx,uint8_t count,float lat,float lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN]; - _mav_put_float(buf, 0, lat); - _mav_put_float(buf, 4, lng); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t(buf, 10, idx); - _mav_put_uint8_t(buf, 11, count); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#else - mavlink_fence_point_t packet; - packet.lat = lat; - packet.lng = lng; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - packet.count = count; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FENCE_POINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#endif -} - -/** - * @brief Encode a fence_point struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param fence_point C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point) -{ - return mavlink_msg_fence_point_pack(system_id, component_id, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng); -} - -/** - * @brief Encode a fence_point struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param fence_point C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_fence_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point) -{ - return mavlink_msg_fence_point_pack_chan(system_id, component_id, chan, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng); -} - -/** - * @brief Send a fence_point message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 1, 0 is for return point) - * @param count total number of points (for sanity checking) - * @param lat Latitude of point - * @param lng Longitude of point - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN]; - _mav_put_float(buf, 0, lat); - _mav_put_float(buf, 4, lng); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t(buf, 10, idx); - _mav_put_uint8_t(buf, 11, count); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#endif -#else - mavlink_fence_point_t packet; - packet.lat = lat; - packet.lng = lng; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - packet.count = count; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FENCE_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_fence_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, lat); - _mav_put_float(buf, 4, lng); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_uint8_t(buf, 10, idx); - _mav_put_uint8_t(buf, 11, count); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#endif -#else - mavlink_fence_point_t *packet = (mavlink_fence_point_t *)msgbuf; - packet->lat = lat; - packet->lng = lng; - packet->target_system = target_system; - packet->target_component = target_component; - packet->idx = idx; - packet->count = count; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_POINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FENCE_POINT UNPACKING - - -/** - * @brief Get field target_system from fence_point message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_fence_point_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field target_component from fence_point message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_fence_point_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Get field idx from fence_point message - * - * @return point index (first point is 1, 0 is for return point) - */ -static inline uint8_t mavlink_msg_fence_point_get_idx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field count from fence_point message - * - * @return total number of points (for sanity checking) - */ -static inline uint8_t mavlink_msg_fence_point_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field lat from fence_point message - * - * @return Latitude of point - */ -static inline float mavlink_msg_fence_point_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field lng from fence_point message - * - * @return Longitude of point - */ -static inline float mavlink_msg_fence_point_get_lng(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a fence_point message into a struct - * - * @param msg The message to decode - * @param fence_point C-struct to decode the message contents into - */ -static inline void mavlink_msg_fence_point_decode(const mavlink_message_t* msg, mavlink_fence_point_t* fence_point) -{ -#if MAVLINK_NEED_BYTE_SWAP - fence_point->lat = mavlink_msg_fence_point_get_lat(msg); - fence_point->lng = mavlink_msg_fence_point_get_lng(msg); - fence_point->target_system = mavlink_msg_fence_point_get_target_system(msg); - fence_point->target_component = mavlink_msg_fence_point_get_target_component(msg); - fence_point->idx = mavlink_msg_fence_point_get_idx(msg); - fence_point->count = mavlink_msg_fence_point_get_count(msg); -#else - memcpy(fence_point, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FENCE_POINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h deleted file mode 100644 index c50d37724..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE FENCE_STATUS PACKING - -#define MAVLINK_MSG_ID_FENCE_STATUS 162 - -typedef struct __mavlink_fence_status_t -{ - uint32_t breach_time; ///< time of last breach in milliseconds since boot - uint16_t breach_count; ///< number of fence breaches - uint8_t breach_status; ///< 0 if currently inside fence, 1 if outside - uint8_t breach_type; ///< last breach type (see FENCE_BREACH_* enum) -} mavlink_fence_status_t; - -#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8 -#define MAVLINK_MSG_ID_162_LEN 8 - -#define MAVLINK_MSG_ID_FENCE_STATUS_CRC 189 -#define MAVLINK_MSG_ID_162_CRC 189 - - - -#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \ - "FENCE_STATUS", \ - 4, \ - { { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \ - { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \ - { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \ - { "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \ - } \ -} - - -/** - * @brief Pack a fence_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param breach_status 0 if currently inside fence, 1 if outside - * @param breach_count number of fence breaches - * @param breach_type last breach type (see FENCE_BREACH_* enum) - * @param breach_time time of last breach in milliseconds since boot - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, breach_time); - _mav_put_uint16_t(buf, 4, breach_count); - _mav_put_uint8_t(buf, 6, breach_status); - _mav_put_uint8_t(buf, 7, breach_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#else - mavlink_fence_status_t packet; - packet.breach_time = breach_time; - packet.breach_count = breach_count; - packet.breach_status = breach_status; - packet.breach_type = breach_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif -} - -/** - * @brief Pack a fence_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param breach_status 0 if currently inside fence, 1 if outside - * @param breach_count number of fence breaches - * @param breach_type last breach type (see FENCE_BREACH_* enum) - * @param breach_time time of last breach in milliseconds since boot - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, breach_time); - _mav_put_uint16_t(buf, 4, breach_count); - _mav_put_uint8_t(buf, 6, breach_status); - _mav_put_uint8_t(buf, 7, breach_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#else - mavlink_fence_status_t packet; - packet.breach_time = breach_time; - packet.breach_count = breach_count; - packet.breach_status = breach_status; - packet.breach_type = breach_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif -} - -/** - * @brief Encode a fence_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param fence_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status) -{ - return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time); -} - -/** - * @brief Encode a fence_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param fence_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status) -{ - return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time); -} - -/** - * @brief Send a fence_status message - * @param chan MAVLink channel to send the message - * - * @param breach_status 0 if currently inside fence, 1 if outside - * @param breach_count number of fence breaches - * @param breach_type last breach type (see FENCE_BREACH_* enum) - * @param breach_time time of last breach in milliseconds since boot - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, breach_time); - _mav_put_uint16_t(buf, 4, breach_count); - _mav_put_uint8_t(buf, 6, breach_status); - _mav_put_uint8_t(buf, 7, breach_type); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif -#else - mavlink_fence_status_t packet; - packet.breach_time = breach_time; - packet.breach_count = breach_count; - packet.breach_status = breach_status; - packet.breach_type = breach_type; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FENCE_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, breach_time); - _mav_put_uint16_t(buf, 4, breach_count); - _mav_put_uint8_t(buf, 6, breach_status); - _mav_put_uint8_t(buf, 7, breach_type); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif -#else - mavlink_fence_status_t *packet = (mavlink_fence_status_t *)msgbuf; - packet->breach_time = breach_time; - packet->breach_count = breach_count; - packet->breach_status = breach_status; - packet->breach_type = breach_type; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FENCE_STATUS UNPACKING - - -/** - * @brief Get field breach_status from fence_status message - * - * @return 0 if currently inside fence, 1 if outside - */ -static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field breach_count from fence_status message - * - * @return number of fence breaches - */ -static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field breach_type from fence_status message - * - * @return last breach type (see FENCE_BREACH_* enum) - */ -static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field breach_time from fence_status message - * - * @return time of last breach in milliseconds since boot - */ -static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Decode a fence_status message into a struct - * - * @param msg The message to decode - * @param fence_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg); - fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg); - fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg); - fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg); -#else - memcpy(fence_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FENCE_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h deleted file mode 100644 index acf031f62..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE HWSTATUS PACKING - -#define MAVLINK_MSG_ID_HWSTATUS 165 - -typedef struct __mavlink_hwstatus_t -{ - uint16_t Vcc; ///< board voltage (mV) - uint8_t I2Cerr; ///< I2C error count -} mavlink_hwstatus_t; - -#define MAVLINK_MSG_ID_HWSTATUS_LEN 3 -#define MAVLINK_MSG_ID_165_LEN 3 - -#define MAVLINK_MSG_ID_HWSTATUS_CRC 21 -#define MAVLINK_MSG_ID_165_CRC 21 - - - -#define MAVLINK_MESSAGE_INFO_HWSTATUS { \ - "HWSTATUS", \ - 2, \ - { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hwstatus_t, Vcc) }, \ - { "I2Cerr", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_hwstatus_t, I2Cerr) }, \ - } \ -} - - -/** - * @brief Pack a hwstatus message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param Vcc board voltage (mV) - * @param I2Cerr I2C error count - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t Vcc, uint8_t I2Cerr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HWSTATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint8_t(buf, 2, I2Cerr); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HWSTATUS_LEN); -#else - mavlink_hwstatus_t packet; - packet.Vcc = Vcc; - packet.I2Cerr = I2Cerr; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HWSTATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HWSTATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HWSTATUS_LEN); -#endif -} - -/** - * @brief Pack a hwstatus message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param Vcc board voltage (mV) - * @param I2Cerr I2C error count - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t Vcc,uint8_t I2Cerr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HWSTATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint8_t(buf, 2, I2Cerr); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HWSTATUS_LEN); -#else - mavlink_hwstatus_t packet; - packet.Vcc = Vcc; - packet.I2Cerr = I2Cerr; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HWSTATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HWSTATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HWSTATUS_LEN); -#endif -} - -/** - * @brief Encode a hwstatus struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hwstatus C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus) -{ - return mavlink_msg_hwstatus_pack(system_id, component_id, msg, hwstatus->Vcc, hwstatus->I2Cerr); -} - -/** - * @brief Encode a hwstatus struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hwstatus C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hwstatus_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus) -{ - return mavlink_msg_hwstatus_pack_chan(system_id, component_id, chan, msg, hwstatus->Vcc, hwstatus->I2Cerr); -} - -/** - * @brief Send a hwstatus message - * @param chan MAVLink channel to send the message - * - * @param Vcc board voltage (mV) - * @param I2Cerr I2C error count - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hwstatus_send(mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HWSTATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint8_t(buf, 2, I2Cerr); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_LEN); -#endif -#else - mavlink_hwstatus_t packet; - packet.Vcc = Vcc; - packet.I2Cerr = I2Cerr; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, MAVLINK_MSG_ID_HWSTATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HWSTATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hwstatus_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint8_t(buf, 2, I2Cerr); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_LEN); -#endif -#else - mavlink_hwstatus_t *packet = (mavlink_hwstatus_t *)msgbuf; - packet->Vcc = Vcc; - packet->I2Cerr = I2Cerr; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)packet, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)packet, MAVLINK_MSG_ID_HWSTATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HWSTATUS UNPACKING - - -/** - * @brief Get field Vcc from hwstatus message - * - * @return board voltage (mV) - */ -static inline uint16_t mavlink_msg_hwstatus_get_Vcc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field I2Cerr from hwstatus message - * - * @return I2C error count - */ -static inline uint8_t mavlink_msg_hwstatus_get_I2Cerr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a hwstatus message into a struct - * - * @param msg The message to decode - * @param hwstatus C-struct to decode the message contents into - */ -static inline void mavlink_msg_hwstatus_decode(const mavlink_message_t* msg, mavlink_hwstatus_t* hwstatus) -{ -#if MAVLINK_NEED_BYTE_SWAP - hwstatus->Vcc = mavlink_msg_hwstatus_get_Vcc(msg); - hwstatus->I2Cerr = mavlink_msg_hwstatus_get_I2Cerr(msg); -#else - memcpy(hwstatus, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HWSTATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h deleted file mode 100644 index 5fef93718..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_limits_status.h +++ /dev/null @@ -1,401 +0,0 @@ -// MESSAGE LIMITS_STATUS PACKING - -#define MAVLINK_MSG_ID_LIMITS_STATUS 167 - -typedef struct __mavlink_limits_status_t -{ - uint32_t last_trigger; ///< time of last breach in milliseconds since boot - uint32_t last_action; ///< time of last recovery action in milliseconds since boot - uint32_t last_recovery; ///< time of last successful recovery in milliseconds since boot - uint32_t last_clear; ///< time of last all-clear in milliseconds since boot - uint16_t breach_count; ///< number of fence breaches - uint8_t limits_state; ///< state of AP_Limits, (see enum LimitState, LIMITS_STATE) - uint8_t mods_enabled; ///< AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) - uint8_t mods_required; ///< AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) - uint8_t mods_triggered; ///< AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) -} mavlink_limits_status_t; - -#define MAVLINK_MSG_ID_LIMITS_STATUS_LEN 22 -#define MAVLINK_MSG_ID_167_LEN 22 - -#define MAVLINK_MSG_ID_LIMITS_STATUS_CRC 144 -#define MAVLINK_MSG_ID_167_CRC 144 - - - -#define MAVLINK_MESSAGE_INFO_LIMITS_STATUS { \ - "LIMITS_STATUS", \ - 9, \ - { { "last_trigger", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_limits_status_t, last_trigger) }, \ - { "last_action", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_limits_status_t, last_action) }, \ - { "last_recovery", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_limits_status_t, last_recovery) }, \ - { "last_clear", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_limits_status_t, last_clear) }, \ - { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_limits_status_t, breach_count) }, \ - { "limits_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_limits_status_t, limits_state) }, \ - { "mods_enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_limits_status_t, mods_enabled) }, \ - { "mods_required", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_limits_status_t, mods_required) }, \ - { "mods_triggered", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_limits_status_t, mods_triggered) }, \ - } \ -} - - -/** - * @brief Pack a limits_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param limits_state state of AP_Limits, (see enum LimitState, LIMITS_STATE) - * @param last_trigger time of last breach in milliseconds since boot - * @param last_action time of last recovery action in milliseconds since boot - * @param last_recovery time of last successful recovery in milliseconds since boot - * @param last_clear time of last all-clear in milliseconds since boot - * @param breach_count number of fence breaches - * @param mods_enabled AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) - * @param mods_required AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) - * @param mods_triggered AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_limits_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, last_trigger); - _mav_put_uint32_t(buf, 4, last_action); - _mav_put_uint32_t(buf, 8, last_recovery); - _mav_put_uint32_t(buf, 12, last_clear); - _mav_put_uint16_t(buf, 16, breach_count); - _mav_put_uint8_t(buf, 18, limits_state); - _mav_put_uint8_t(buf, 19, mods_enabled); - _mav_put_uint8_t(buf, 20, mods_required); - _mav_put_uint8_t(buf, 21, mods_triggered); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#else - mavlink_limits_status_t packet; - packet.last_trigger = last_trigger; - packet.last_action = last_action; - packet.last_recovery = last_recovery; - packet.last_clear = last_clear; - packet.breach_count = breach_count; - packet.limits_state = limits_state; - packet.mods_enabled = mods_enabled; - packet.mods_required = mods_required; - packet.mods_triggered = mods_triggered; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#endif -} - -/** - * @brief Pack a limits_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param limits_state state of AP_Limits, (see enum LimitState, LIMITS_STATE) - * @param last_trigger time of last breach in milliseconds since boot - * @param last_action time of last recovery action in milliseconds since boot - * @param last_recovery time of last successful recovery in milliseconds since boot - * @param last_clear time of last all-clear in milliseconds since boot - * @param breach_count number of fence breaches - * @param mods_enabled AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) - * @param mods_required AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) - * @param mods_triggered AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_limits_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t limits_state,uint32_t last_trigger,uint32_t last_action,uint32_t last_recovery,uint32_t last_clear,uint16_t breach_count,uint8_t mods_enabled,uint8_t mods_required,uint8_t mods_triggered) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, last_trigger); - _mav_put_uint32_t(buf, 4, last_action); - _mav_put_uint32_t(buf, 8, last_recovery); - _mav_put_uint32_t(buf, 12, last_clear); - _mav_put_uint16_t(buf, 16, breach_count); - _mav_put_uint8_t(buf, 18, limits_state); - _mav_put_uint8_t(buf, 19, mods_enabled); - _mav_put_uint8_t(buf, 20, mods_required); - _mav_put_uint8_t(buf, 21, mods_triggered); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#else - mavlink_limits_status_t packet; - packet.last_trigger = last_trigger; - packet.last_action = last_action; - packet.last_recovery = last_recovery; - packet.last_clear = last_clear; - packet.breach_count = breach_count; - packet.limits_state = limits_state; - packet.mods_enabled = mods_enabled; - packet.mods_required = mods_required; - packet.mods_triggered = mods_triggered; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#endif -} - -/** - * @brief Encode a limits_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param limits_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_limits_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_limits_status_t* limits_status) -{ - return mavlink_msg_limits_status_pack(system_id, component_id, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered); -} - -/** - * @brief Encode a limits_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param limits_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_limits_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_limits_status_t* limits_status) -{ - return mavlink_msg_limits_status_pack_chan(system_id, component_id, chan, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered); -} - -/** - * @brief Send a limits_status message - * @param chan MAVLink channel to send the message - * - * @param limits_state state of AP_Limits, (see enum LimitState, LIMITS_STATE) - * @param last_trigger time of last breach in milliseconds since boot - * @param last_action time of last recovery action in milliseconds since boot - * @param last_recovery time of last successful recovery in milliseconds since boot - * @param last_clear time of last all-clear in milliseconds since boot - * @param breach_count number of fence breaches - * @param mods_enabled AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) - * @param mods_required AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) - * @param mods_triggered AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_limits_status_send(mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, last_trigger); - _mav_put_uint32_t(buf, 4, last_action); - _mav_put_uint32_t(buf, 8, last_recovery); - _mav_put_uint32_t(buf, 12, last_clear); - _mav_put_uint16_t(buf, 16, breach_count); - _mav_put_uint8_t(buf, 18, limits_state); - _mav_put_uint8_t(buf, 19, mods_enabled); - _mav_put_uint8_t(buf, 20, mods_required); - _mav_put_uint8_t(buf, 21, mods_triggered); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#endif -#else - mavlink_limits_status_t packet; - packet.last_trigger = last_trigger; - packet.last_action = last_action; - packet.last_recovery = last_recovery; - packet.last_clear = last_clear; - packet.breach_count = breach_count; - packet.limits_state = limits_state; - packet.mods_enabled = mods_enabled; - packet.mods_required = mods_required; - packet.mods_triggered = mods_triggered; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LIMITS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_limits_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, last_trigger); - _mav_put_uint32_t(buf, 4, last_action); - _mav_put_uint32_t(buf, 8, last_recovery); - _mav_put_uint32_t(buf, 12, last_clear); - _mav_put_uint16_t(buf, 16, breach_count); - _mav_put_uint8_t(buf, 18, limits_state); - _mav_put_uint8_t(buf, 19, mods_enabled); - _mav_put_uint8_t(buf, 20, mods_required); - _mav_put_uint8_t(buf, 21, mods_triggered); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#endif -#else - mavlink_limits_status_t *packet = (mavlink_limits_status_t *)msgbuf; - packet->last_trigger = last_trigger; - packet->last_action = last_action; - packet->last_recovery = last_recovery; - packet->last_clear = last_clear; - packet->breach_count = breach_count; - packet->limits_state = limits_state; - packet->mods_enabled = mods_enabled; - packet->mods_required = mods_required; - packet->mods_triggered = mods_triggered; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LIMITS_STATUS UNPACKING - - -/** - * @brief Get field limits_state from limits_status message - * - * @return state of AP_Limits, (see enum LimitState, LIMITS_STATE) - */ -static inline uint8_t mavlink_msg_limits_status_get_limits_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field last_trigger from limits_status message - * - * @return time of last breach in milliseconds since boot - */ -static inline uint32_t mavlink_msg_limits_status_get_last_trigger(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field last_action from limits_status message - * - * @return time of last recovery action in milliseconds since boot - */ -static inline uint32_t mavlink_msg_limits_status_get_last_action(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field last_recovery from limits_status message - * - * @return time of last successful recovery in milliseconds since boot - */ -static inline uint32_t mavlink_msg_limits_status_get_last_recovery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field last_clear from limits_status message - * - * @return time of last all-clear in milliseconds since boot - */ -static inline uint32_t mavlink_msg_limits_status_get_last_clear(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 12); -} - -/** - * @brief Get field breach_count from limits_status message - * - * @return number of fence breaches - */ -static inline uint16_t mavlink_msg_limits_status_get_breach_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field mods_enabled from limits_status message - * - * @return AP_Limit_Module bitfield of enabled modules, (see enum moduleid or LIMIT_MODULE) - */ -static inline uint8_t mavlink_msg_limits_status_get_mods_enabled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 19); -} - -/** - * @brief Get field mods_required from limits_status message - * - * @return AP_Limit_Module bitfield of required modules, (see enum moduleid or LIMIT_MODULE) - */ -static inline uint8_t mavlink_msg_limits_status_get_mods_required(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field mods_triggered from limits_status message - * - * @return AP_Limit_Module bitfield of triggered modules, (see enum moduleid or LIMIT_MODULE) - */ -static inline uint8_t mavlink_msg_limits_status_get_mods_triggered(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a limits_status message into a struct - * - * @param msg The message to decode - * @param limits_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_limits_status_decode(const mavlink_message_t* msg, mavlink_limits_status_t* limits_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - limits_status->last_trigger = mavlink_msg_limits_status_get_last_trigger(msg); - limits_status->last_action = mavlink_msg_limits_status_get_last_action(msg); - limits_status->last_recovery = mavlink_msg_limits_status_get_last_recovery(msg); - limits_status->last_clear = mavlink_msg_limits_status_get_last_clear(msg); - limits_status->breach_count = mavlink_msg_limits_status_get_breach_count(msg); - limits_status->limits_state = mavlink_msg_limits_status_get_limits_state(msg); - limits_status->mods_enabled = mavlink_msg_limits_status_get_mods_enabled(msg); - limits_status->mods_required = mavlink_msg_limits_status_get_mods_required(msg); - limits_status->mods_triggered = mavlink_msg_limits_status_get_mods_triggered(msg); -#else - memcpy(limits_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LIMITS_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h deleted file mode 100644 index c64b2e937..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE MEMINFO PACKING - -#define MAVLINK_MSG_ID_MEMINFO 152 - -typedef struct __mavlink_meminfo_t -{ - uint16_t brkval; ///< heap top - uint16_t freemem; ///< free memory -} mavlink_meminfo_t; - -#define MAVLINK_MSG_ID_MEMINFO_LEN 4 -#define MAVLINK_MSG_ID_152_LEN 4 - -#define MAVLINK_MSG_ID_MEMINFO_CRC 208 -#define MAVLINK_MSG_ID_152_CRC 208 - - - -#define MAVLINK_MESSAGE_INFO_MEMINFO { \ - "MEMINFO", \ - 2, \ - { { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \ - { "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \ - } \ -} - - -/** - * @brief Pack a meminfo message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param brkval heap top - * @param freemem free memory - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t brkval, uint16_t freemem) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MEMINFO_LEN]; - _mav_put_uint16_t(buf, 0, brkval); - _mav_put_uint16_t(buf, 2, freemem); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMINFO_LEN); -#else - mavlink_meminfo_t packet; - packet.brkval = brkval; - packet.freemem = freemem; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMINFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MEMINFO; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMINFO_LEN); -#endif -} - -/** - * @brief Pack a meminfo message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param brkval heap top - * @param freemem free memory - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t brkval,uint16_t freemem) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MEMINFO_LEN]; - _mav_put_uint16_t(buf, 0, brkval); - _mav_put_uint16_t(buf, 2, freemem); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMINFO_LEN); -#else - mavlink_meminfo_t packet; - packet.brkval = brkval; - packet.freemem = freemem; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMINFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MEMINFO; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMINFO_LEN); -#endif -} - -/** - * @brief Encode a meminfo struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param meminfo C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo) -{ - return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem); -} - -/** - * @brief Encode a meminfo struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param meminfo C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_meminfo_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo) -{ - return mavlink_msg_meminfo_pack_chan(system_id, component_id, chan, msg, meminfo->brkval, meminfo->freemem); -} - -/** - * @brief Send a meminfo message - * @param chan MAVLink channel to send the message - * - * @param brkval heap top - * @param freemem free memory - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brkval, uint16_t freemem) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MEMINFO_LEN]; - _mav_put_uint16_t(buf, 0, brkval); - _mav_put_uint16_t(buf, 2, freemem); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_LEN); -#endif -#else - mavlink_meminfo_t packet; - packet.brkval = brkval; - packet.freemem = freemem; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, MAVLINK_MSG_ID_MEMINFO_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MEMINFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_meminfo_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t brkval, uint16_t freemem) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, brkval); - _mav_put_uint16_t(buf, 2, freemem); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_LEN); -#endif -#else - mavlink_meminfo_t *packet = (mavlink_meminfo_t *)msgbuf; - packet->brkval = brkval; - packet->freemem = freemem; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)packet, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)packet, MAVLINK_MSG_ID_MEMINFO_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MEMINFO UNPACKING - - -/** - * @brief Get field brkval from meminfo message - * - * @return heap top - */ -static inline uint16_t mavlink_msg_meminfo_get_brkval(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field freemem from meminfo message - * - * @return free memory - */ -static inline uint16_t mavlink_msg_meminfo_get_freemem(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a meminfo message into a struct - * - * @param msg The message to decode - * @param meminfo C-struct to decode the message contents into - */ -static inline void mavlink_msg_meminfo_decode(const mavlink_message_t* msg, mavlink_meminfo_t* meminfo) -{ -#if MAVLINK_NEED_BYTE_SWAP - meminfo->brkval = mavlink_msg_meminfo_get_brkval(msg); - meminfo->freemem = mavlink_msg_meminfo_get_freemem(msg); -#else - memcpy(meminfo, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MEMINFO_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h deleted file mode 100644 index 350bb0b78..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE MOUNT_CONFIGURE PACKING - -#define MAVLINK_MSG_ID_MOUNT_CONFIGURE 156 - -typedef struct __mavlink_mount_configure_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t mount_mode; ///< mount operating mode (see MAV_MOUNT_MODE enum) - uint8_t stab_roll; ///< (1 = yes, 0 = no) - uint8_t stab_pitch; ///< (1 = yes, 0 = no) - uint8_t stab_yaw; ///< (1 = yes, 0 = no) -} mavlink_mount_configure_t; - -#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN 6 -#define MAVLINK_MSG_ID_156_LEN 6 - -#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC 19 -#define MAVLINK_MSG_ID_156_CRC 19 - - - -#define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \ - "MOUNT_CONFIGURE", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_configure_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_configure_t, target_component) }, \ - { "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mount_configure_t, mount_mode) }, \ - { "stab_roll", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mount_configure_t, stab_roll) }, \ - { "stab_pitch", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mount_configure_t, stab_pitch) }, \ - { "stab_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mount_configure_t, stab_yaw) }, \ - } \ -} - - -/** - * @brief Pack a mount_configure message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum) - * @param stab_roll (1 = yes, 0 = no) - * @param stab_pitch (1 = yes, 0 = no) - * @param stab_yaw (1 = yes, 0 = no) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mount_mode); - _mav_put_uint8_t(buf, 3, stab_roll); - _mav_put_uint8_t(buf, 4, stab_pitch); - _mav_put_uint8_t(buf, 5, stab_yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#else - mavlink_mount_configure_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mount_mode = mount_mode; - packet.stab_roll = stab_roll; - packet.stab_pitch = stab_pitch; - packet.stab_yaw = stab_yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#endif -} - -/** - * @brief Pack a mount_configure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum) - * @param stab_roll (1 = yes, 0 = no) - * @param stab_pitch (1 = yes, 0 = no) - * @param stab_yaw (1 = yes, 0 = no) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t mount_mode,uint8_t stab_roll,uint8_t stab_pitch,uint8_t stab_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mount_mode); - _mav_put_uint8_t(buf, 3, stab_roll); - _mav_put_uint8_t(buf, 4, stab_pitch); - _mav_put_uint8_t(buf, 5, stab_yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#else - mavlink_mount_configure_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mount_mode = mount_mode; - packet.stab_roll = stab_roll; - packet.stab_pitch = stab_pitch; - packet.stab_yaw = stab_yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#endif -} - -/** - * @brief Encode a mount_configure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mount_configure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure) -{ - return mavlink_msg_mount_configure_pack(system_id, component_id, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw); -} - -/** - * @brief Encode a mount_configure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mount_configure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure) -{ - return mavlink_msg_mount_configure_pack_chan(system_id, component_id, chan, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw); -} - -/** - * @brief Send a mount_configure message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum) - * @param stab_roll (1 = yes, 0 = no) - * @param stab_pitch (1 = yes, 0 = no) - * @param stab_yaw (1 = yes, 0 = no) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mount_mode); - _mav_put_uint8_t(buf, 3, stab_roll); - _mav_put_uint8_t(buf, 4, stab_pitch); - _mav_put_uint8_t(buf, 5, stab_yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#endif -#else - mavlink_mount_configure_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.mount_mode = mount_mode; - packet.stab_roll = stab_roll; - packet.stab_pitch = stab_pitch; - packet.stab_yaw = stab_yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mount_configure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, mount_mode); - _mav_put_uint8_t(buf, 3, stab_roll); - _mav_put_uint8_t(buf, 4, stab_pitch); - _mav_put_uint8_t(buf, 5, stab_yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#endif -#else - mavlink_mount_configure_t *packet = (mavlink_mount_configure_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->mount_mode = mount_mode; - packet->stab_roll = stab_roll; - packet->stab_pitch = stab_pitch; - packet->stab_yaw = stab_yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MOUNT_CONFIGURE UNPACKING - - -/** - * @brief Get field target_system from mount_configure message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mount_configure_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mount_configure message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mount_configure_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field mount_mode from mount_configure message - * - * @return mount operating mode (see MAV_MOUNT_MODE enum) - */ -static inline uint8_t mavlink_msg_mount_configure_get_mount_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field stab_roll from mount_configure message - * - * @return (1 = yes, 0 = no) - */ -static inline uint8_t mavlink_msg_mount_configure_get_stab_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field stab_pitch from mount_configure message - * - * @return (1 = yes, 0 = no) - */ -static inline uint8_t mavlink_msg_mount_configure_get_stab_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field stab_yaw from mount_configure message - * - * @return (1 = yes, 0 = no) - */ -static inline uint8_t mavlink_msg_mount_configure_get_stab_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Decode a mount_configure message into a struct - * - * @param msg The message to decode - * @param mount_configure C-struct to decode the message contents into - */ -static inline void mavlink_msg_mount_configure_decode(const mavlink_message_t* msg, mavlink_mount_configure_t* mount_configure) -{ -#if MAVLINK_NEED_BYTE_SWAP - mount_configure->target_system = mavlink_msg_mount_configure_get_target_system(msg); - mount_configure->target_component = mavlink_msg_mount_configure_get_target_component(msg); - mount_configure->mount_mode = mavlink_msg_mount_configure_get_mount_mode(msg); - mount_configure->stab_roll = mavlink_msg_mount_configure_get_stab_roll(msg); - mount_configure->stab_pitch = mavlink_msg_mount_configure_get_stab_pitch(msg); - mount_configure->stab_yaw = mavlink_msg_mount_configure_get_stab_yaw(msg); -#else - memcpy(mount_configure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h deleted file mode 100644 index 72d6e2419..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE MOUNT_CONTROL PACKING - -#define MAVLINK_MSG_ID_MOUNT_CONTROL 157 - -typedef struct __mavlink_mount_control_t -{ - int32_t input_a; ///< pitch(deg*100) or lat, depending on mount mode - int32_t input_b; ///< roll(deg*100) or lon depending on mount mode - int32_t input_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t save_position; ///< if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) -} mavlink_mount_control_t; - -#define MAVLINK_MSG_ID_MOUNT_CONTROL_LEN 15 -#define MAVLINK_MSG_ID_157_LEN 15 - -#define MAVLINK_MSG_ID_MOUNT_CONTROL_CRC 21 -#define MAVLINK_MSG_ID_157_CRC 21 - - - -#define MAVLINK_MESSAGE_INFO_MOUNT_CONTROL { \ - "MOUNT_CONTROL", \ - 6, \ - { { "input_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_control_t, input_a) }, \ - { "input_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_control_t, input_b) }, \ - { "input_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_control_t, input_c) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_control_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_control_t, target_component) }, \ - { "save_position", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_control_t, save_position) }, \ - } \ -} - - -/** - * @brief Pack a mount_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param input_a pitch(deg*100) or lat, depending on mount mode - * @param input_b roll(deg*100) or lon depending on mount mode - * @param input_c yaw(deg*100) or alt (in cm) depending on mount mode - * @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN]; - _mav_put_int32_t(buf, 0, input_a); - _mav_put_int32_t(buf, 4, input_b); - _mav_put_int32_t(buf, 8, input_c); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - _mav_put_uint8_t(buf, 14, save_position); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#else - mavlink_mount_control_t packet; - packet.input_a = input_a; - packet.input_b = input_b; - packet.input_c = input_c; - packet.target_system = target_system; - packet.target_component = target_component; - packet.save_position = save_position; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#endif -} - -/** - * @brief Pack a mount_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param input_a pitch(deg*100) or lat, depending on mount mode - * @param input_b roll(deg*100) or lon depending on mount mode - * @param input_c yaw(deg*100) or alt (in cm) depending on mount mode - * @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int32_t input_a,int32_t input_b,int32_t input_c,uint8_t save_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN]; - _mav_put_int32_t(buf, 0, input_a); - _mav_put_int32_t(buf, 4, input_b); - _mav_put_int32_t(buf, 8, input_c); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - _mav_put_uint8_t(buf, 14, save_position); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#else - mavlink_mount_control_t packet; - packet.input_a = input_a; - packet.input_b = input_b; - packet.input_c = input_c; - packet.target_system = target_system; - packet.target_component = target_component; - packet.save_position = save_position; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#endif -} - -/** - * @brief Encode a mount_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mount_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control) -{ - return mavlink_msg_mount_control_pack(system_id, component_id, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position); -} - -/** - * @brief Encode a mount_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mount_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control) -{ - return mavlink_msg_mount_control_pack_chan(system_id, component_id, chan, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position); -} - -/** - * @brief Send a mount_control message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param input_a pitch(deg*100) or lat, depending on mount mode - * @param input_b roll(deg*100) or lon depending on mount mode - * @param input_c yaw(deg*100) or alt (in cm) depending on mount mode - * @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN]; - _mav_put_int32_t(buf, 0, input_a); - _mav_put_int32_t(buf, 4, input_b); - _mav_put_int32_t(buf, 8, input_c); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - _mav_put_uint8_t(buf, 14, save_position); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#endif -#else - mavlink_mount_control_t packet; - packet.input_a = input_a; - packet.input_b = input_b; - packet.input_c = input_c; - packet.target_system = target_system; - packet.target_component = target_component; - packet.save_position = save_position; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MOUNT_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mount_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, input_a); - _mav_put_int32_t(buf, 4, input_b); - _mav_put_int32_t(buf, 8, input_c); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - _mav_put_uint8_t(buf, 14, save_position); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#endif -#else - mavlink_mount_control_t *packet = (mavlink_mount_control_t *)msgbuf; - packet->input_a = input_a; - packet->input_b = input_b; - packet->input_c = input_c; - packet->target_system = target_system; - packet->target_component = target_component; - packet->save_position = save_position; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MOUNT_CONTROL UNPACKING - - -/** - * @brief Get field target_system from mount_control message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mount_control_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field target_component from mount_control message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mount_control_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Get field input_a from mount_control message - * - * @return pitch(deg*100) or lat, depending on mount mode - */ -static inline int32_t mavlink_msg_mount_control_get_input_a(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field input_b from mount_control message - * - * @return roll(deg*100) or lon depending on mount mode - */ -static inline int32_t mavlink_msg_mount_control_get_input_b(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field input_c from mount_control message - * - * @return yaw(deg*100) or alt (in cm) depending on mount mode - */ -static inline int32_t mavlink_msg_mount_control_get_input_c(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field save_position from mount_control message - * - * @return if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING) - */ -static inline uint8_t mavlink_msg_mount_control_get_save_position(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Decode a mount_control message into a struct - * - * @param msg The message to decode - * @param mount_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_mount_control_decode(const mavlink_message_t* msg, mavlink_mount_control_t* mount_control) -{ -#if MAVLINK_NEED_BYTE_SWAP - mount_control->input_a = mavlink_msg_mount_control_get_input_a(msg); - mount_control->input_b = mavlink_msg_mount_control_get_input_b(msg); - mount_control->input_c = mavlink_msg_mount_control_get_input_c(msg); - mount_control->target_system = mavlink_msg_mount_control_get_target_system(msg); - mount_control->target_component = mavlink_msg_mount_control_get_target_component(msg); - mount_control->save_position = mavlink_msg_mount_control_get_save_position(msg); -#else - memcpy(mount_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MOUNT_CONTROL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h deleted file mode 100644 index c140dd2c7..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE MOUNT_STATUS PACKING - -#define MAVLINK_MSG_ID_MOUNT_STATUS 158 - -typedef struct __mavlink_mount_status_t -{ - int32_t pointing_a; ///< pitch(deg*100) or lat, depending on mount mode - int32_t pointing_b; ///< roll(deg*100) or lon depending on mount mode - int32_t pointing_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_mount_status_t; - -#define MAVLINK_MSG_ID_MOUNT_STATUS_LEN 14 -#define MAVLINK_MSG_ID_158_LEN 14 - -#define MAVLINK_MSG_ID_MOUNT_STATUS_CRC 134 -#define MAVLINK_MSG_ID_158_CRC 134 - - - -#define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \ - "MOUNT_STATUS", \ - 5, \ - { { "pointing_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_status_t, pointing_a) }, \ - { "pointing_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_status_t, pointing_b) }, \ - { "pointing_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_status_t, pointing_c) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_status_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_status_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a mount_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param pointing_a pitch(deg*100) or lat, depending on mount mode - * @param pointing_b roll(deg*100) or lon depending on mount mode - * @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN]; - _mav_put_int32_t(buf, 0, pointing_a); - _mav_put_int32_t(buf, 4, pointing_b); - _mav_put_int32_t(buf, 8, pointing_c); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#else - mavlink_mount_status_t packet; - packet.pointing_a = pointing_a; - packet.pointing_b = pointing_b; - packet.pointing_c = pointing_c; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#endif -} - -/** - * @brief Pack a mount_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param pointing_a pitch(deg*100) or lat, depending on mount mode - * @param pointing_b roll(deg*100) or lon depending on mount mode - * @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int32_t pointing_a,int32_t pointing_b,int32_t pointing_c) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN]; - _mav_put_int32_t(buf, 0, pointing_a); - _mav_put_int32_t(buf, 4, pointing_b); - _mav_put_int32_t(buf, 8, pointing_c); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#else - mavlink_mount_status_t packet; - packet.pointing_a = pointing_a; - packet.pointing_b = pointing_b; - packet.pointing_c = pointing_c; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#endif -} - -/** - * @brief Encode a mount_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mount_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status) -{ - return mavlink_msg_mount_status_pack(system_id, component_id, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c); -} - -/** - * @brief Encode a mount_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mount_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mount_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status) -{ - return mavlink_msg_mount_status_pack_chan(system_id, component_id, chan, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c); -} - -/** - * @brief Send a mount_status message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param pointing_a pitch(deg*100) or lat, depending on mount mode - * @param pointing_b roll(deg*100) or lon depending on mount mode - * @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN]; - _mav_put_int32_t(buf, 0, pointing_a); - _mav_put_int32_t(buf, 4, pointing_b); - _mav_put_int32_t(buf, 8, pointing_c); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#endif -#else - mavlink_mount_status_t packet; - packet.pointing_a = pointing_a; - packet.pointing_b = pointing_b; - packet.pointing_c = pointing_c; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MOUNT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mount_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, pointing_a); - _mav_put_int32_t(buf, 4, pointing_b); - _mav_put_int32_t(buf, 8, pointing_c); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#endif -#else - mavlink_mount_status_t *packet = (mavlink_mount_status_t *)msgbuf; - packet->pointing_a = pointing_a; - packet->pointing_b = pointing_b; - packet->pointing_c = pointing_c; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MOUNT_STATUS UNPACKING - - -/** - * @brief Get field target_system from mount_status message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mount_status_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field target_component from mount_status message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mount_status_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Get field pointing_a from mount_status message - * - * @return pitch(deg*100) or lat, depending on mount mode - */ -static inline int32_t mavlink_msg_mount_status_get_pointing_a(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field pointing_b from mount_status message - * - * @return roll(deg*100) or lon depending on mount mode - */ -static inline int32_t mavlink_msg_mount_status_get_pointing_b(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field pointing_c from mount_status message - * - * @return yaw(deg*100) or alt (in cm) depending on mount mode - */ -static inline int32_t mavlink_msg_mount_status_get_pointing_c(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Decode a mount_status message into a struct - * - * @param msg The message to decode - * @param mount_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_mount_status_decode(const mavlink_message_t* msg, mavlink_mount_status_t* mount_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - mount_status->pointing_a = mavlink_msg_mount_status_get_pointing_a(msg); - mount_status->pointing_b = mavlink_msg_mount_status_get_pointing_b(msg); - mount_status->pointing_c = mavlink_msg_mount_status_get_pointing_c(msg); - mount_status->target_system = mavlink_msg_mount_status_get_target_system(msg); - mount_status->target_component = mavlink_msg_mount_status_get_target_component(msg); -#else - memcpy(mount_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MOUNT_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h deleted file mode 100644 index 830eb4639..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE RADIO PACKING - -#define MAVLINK_MSG_ID_RADIO 166 - -typedef struct __mavlink_radio_t -{ - uint16_t rxerrors; ///< receive errors - uint16_t fixed; ///< count of error corrected packets - uint8_t rssi; ///< local signal strength - uint8_t remrssi; ///< remote signal strength - uint8_t txbuf; ///< how full the tx buffer is as a percentage - uint8_t noise; ///< background noise level - uint8_t remnoise; ///< remote background noise level -} mavlink_radio_t; - -#define MAVLINK_MSG_ID_RADIO_LEN 9 -#define MAVLINK_MSG_ID_166_LEN 9 - -#define MAVLINK_MSG_ID_RADIO_CRC 21 -#define MAVLINK_MSG_ID_166_CRC 21 - - - -#define MAVLINK_MESSAGE_INFO_RADIO { \ - "RADIO", \ - 7, \ - { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, fixed) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, rssi) }, \ - { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_t, remrssi) }, \ - { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \ - { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, noise) }, \ - { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, remnoise) }, \ - } \ -} - - -/** - * @brief Pack a radio message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param rssi local signal strength - * @param remrssi remote signal strength - * @param txbuf how full the tx buffer is as a percentage - * @param noise background noise level - * @param remnoise remote background noise level - * @param rxerrors receive errors - * @param fixed count of error corrected packets - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RADIO_LEN]; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_LEN); -#else - mavlink_radio_t packet; - packet.rxerrors = rxerrors; - packet.fixed = fixed; - packet.rssi = rssi; - packet.remrssi = remrssi; - packet.txbuf = txbuf; - packet.noise = noise; - packet.remnoise = remnoise; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RADIO; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_LEN); -#endif -} - -/** - * @brief Pack a radio message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rssi local signal strength - * @param remrssi remote signal strength - * @param txbuf how full the tx buffer is as a percentage - * @param noise background noise level - * @param remnoise remote background noise level - * @param rxerrors receive errors - * @param fixed count of error corrected packets - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RADIO_LEN]; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_LEN); -#else - mavlink_radio_t packet; - packet.rxerrors = rxerrors; - packet.fixed = fixed; - packet.rssi = rssi; - packet.remrssi = remrssi; - packet.txbuf = txbuf; - packet.noise = noise; - packet.remnoise = remnoise; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RADIO; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_LEN); -#endif -} - -/** - * @brief Encode a radio struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param radio C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio) -{ - return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed); -} - -/** - * @brief Encode a radio struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param radio C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_radio_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_t* radio) -{ - return mavlink_msg_radio_pack_chan(system_id, component_id, chan, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed); -} - -/** - * @brief Send a radio message - * @param chan MAVLink channel to send the message - * - * @param rssi local signal strength - * @param remrssi remote signal strength - * @param txbuf how full the tx buffer is as a percentage - * @param noise background noise level - * @param remnoise remote background noise level - * @param rxerrors receive errors - * @param fixed count of error corrected packets - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RADIO_LEN]; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_LEN); -#endif -#else - mavlink_radio_t packet; - packet.rxerrors = rxerrors; - packet.fixed = fixed; - packet.rssi = rssi; - packet.remrssi = remrssi; - packet.txbuf = txbuf; - packet.noise = noise; - packet.remnoise = remnoise; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, MAVLINK_MSG_ID_RADIO_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RADIO_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_radio_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_LEN); -#endif -#else - mavlink_radio_t *packet = (mavlink_radio_t *)msgbuf; - packet->rxerrors = rxerrors; - packet->fixed = fixed; - packet->rssi = rssi; - packet->remrssi = remrssi; - packet->txbuf = txbuf; - packet->noise = noise; - packet->remnoise = remnoise; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)packet, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)packet, MAVLINK_MSG_ID_RADIO_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RADIO UNPACKING - - -/** - * @brief Get field rssi from radio message - * - * @return local signal strength - */ -static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field remrssi from radio message - * - * @return remote signal strength - */ -static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field txbuf from radio message - * - * @return how full the tx buffer is as a percentage - */ -static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field noise from radio message - * - * @return background noise level - */ -static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field remnoise from radio message - * - * @return remote background noise level - */ -static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field rxerrors from radio message - * - * @return receive errors - */ -static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field fixed from radio message - * - * @return count of error corrected packets - */ -static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a radio message into a struct - * - * @param msg The message to decode - * @param radio C-struct to decode the message contents into - */ -static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlink_radio_t* radio) -{ -#if MAVLINK_NEED_BYTE_SWAP - radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg); - radio->fixed = mavlink_msg_radio_get_fixed(msg); - radio->rssi = mavlink_msg_radio_get_rssi(msg); - radio->remrssi = mavlink_msg_radio_get_remrssi(msg); - radio->txbuf = mavlink_msg_radio_get_txbuf(msg); - radio->noise = mavlink_msg_radio_get_noise(msg); - radio->remnoise = mavlink_msg_radio_get_remnoise(msg); -#else - memcpy(radio, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RADIO_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h deleted file mode 100644 index 4598251fe..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_fetch_point.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE RALLY_FETCH_POINT PACKING - -#define MAVLINK_MSG_ID_RALLY_FETCH_POINT 176 - -typedef struct __mavlink_rally_fetch_point_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t idx; ///< point index (first point is 0) -} mavlink_rally_fetch_point_t; - -#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN 3 -#define MAVLINK_MSG_ID_176_LEN 3 - -#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC 234 -#define MAVLINK_MSG_ID_176_CRC 234 - - - -#define MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT { \ - "RALLY_FETCH_POINT", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rally_fetch_point_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rally_fetch_point_t, target_component) }, \ - { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_rally_fetch_point_t, idx) }, \ - } \ -} - - -/** - * @brief Pack a rally_fetch_point message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 0) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rally_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t idx) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, idx); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#else - mavlink_rally_fetch_point_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RALLY_FETCH_POINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#endif -} - -/** - * @brief Pack a rally_fetch_point message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 0) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rally_fetch_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t idx) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, idx); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#else - mavlink_rally_fetch_point_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RALLY_FETCH_POINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#endif -} - -/** - * @brief Encode a rally_fetch_point struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rally_fetch_point C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rally_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rally_fetch_point_t* rally_fetch_point) -{ - return mavlink_msg_rally_fetch_point_pack(system_id, component_id, msg, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx); -} - -/** - * @brief Encode a rally_fetch_point struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rally_fetch_point C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rally_fetch_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rally_fetch_point_t* rally_fetch_point) -{ - return mavlink_msg_rally_fetch_point_pack_chan(system_id, component_id, chan, msg, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx); -} - -/** - * @brief Send a rally_fetch_point message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 0) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rally_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, idx); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#endif -#else - mavlink_rally_fetch_point_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rally_fetch_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, idx); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#endif -#else - mavlink_rally_fetch_point_t *packet = (mavlink_rally_fetch_point_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->idx = idx; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RALLY_FETCH_POINT UNPACKING - - -/** - * @brief Get field target_system from rally_fetch_point message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_rally_fetch_point_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from rally_fetch_point message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_rally_fetch_point_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field idx from rally_fetch_point message - * - * @return point index (first point is 0) - */ -static inline uint8_t mavlink_msg_rally_fetch_point_get_idx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a rally_fetch_point message into a struct - * - * @param msg The message to decode - * @param rally_fetch_point C-struct to decode the message contents into - */ -static inline void mavlink_msg_rally_fetch_point_decode(const mavlink_message_t* msg, mavlink_rally_fetch_point_t* rally_fetch_point) -{ -#if MAVLINK_NEED_BYTE_SWAP - rally_fetch_point->target_system = mavlink_msg_rally_fetch_point_get_target_system(msg); - rally_fetch_point->target_component = mavlink_msg_rally_fetch_point_get_target_component(msg); - rally_fetch_point->idx = mavlink_msg_rally_fetch_point_get_idx(msg); -#else - memcpy(rally_fetch_point, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h deleted file mode 100644 index b44e764a9..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rally_point.h +++ /dev/null @@ -1,425 +0,0 @@ -// MESSAGE RALLY_POINT PACKING - -#define MAVLINK_MSG_ID_RALLY_POINT 175 - -typedef struct __mavlink_rally_point_t -{ - int32_t lat; ///< Latitude of point in degrees * 1E7 - int32_t lng; ///< Longitude of point in degrees * 1E7 - int16_t alt; ///< Transit / loiter altitude in meters relative to home - int16_t break_alt; ///< Break altitude in meters relative to home - uint16_t land_dir; ///< Heading to aim for when landing. In centi-degrees. - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t idx; ///< point index (first point is 0) - uint8_t count; ///< total number of points (for sanity checking) - uint8_t flags; ///< See RALLY_FLAGS enum for definition of the bitmask. -} mavlink_rally_point_t; - -#define MAVLINK_MSG_ID_RALLY_POINT_LEN 19 -#define MAVLINK_MSG_ID_175_LEN 19 - -#define MAVLINK_MSG_ID_RALLY_POINT_CRC 138 -#define MAVLINK_MSG_ID_175_CRC 138 - - - -#define MAVLINK_MESSAGE_INFO_RALLY_POINT { \ - "RALLY_POINT", \ - 10, \ - { { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_rally_point_t, lat) }, \ - { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_rally_point_t, lng) }, \ - { "alt", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rally_point_t, alt) }, \ - { "break_alt", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rally_point_t, break_alt) }, \ - { "land_dir", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rally_point_t, land_dir) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_rally_point_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_rally_point_t, target_component) }, \ - { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rally_point_t, idx) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rally_point_t, count) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_rally_point_t, flags) }, \ - } \ -} - - -/** - * @brief Pack a rally_point message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 0) - * @param count total number of points (for sanity checking) - * @param lat Latitude of point in degrees * 1E7 - * @param lng Longitude of point in degrees * 1E7 - * @param alt Transit / loiter altitude in meters relative to home - * @param break_alt Break altitude in meters relative to home - * @param land_dir Heading to aim for when landing. In centi-degrees. - * @param flags See RALLY_FLAGS enum for definition of the bitmask. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rally_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lng); - _mav_put_int16_t(buf, 8, alt); - _mav_put_int16_t(buf, 10, break_alt); - _mav_put_uint16_t(buf, 12, land_dir); - _mav_put_uint8_t(buf, 14, target_system); - _mav_put_uint8_t(buf, 15, target_component); - _mav_put_uint8_t(buf, 16, idx); - _mav_put_uint8_t(buf, 17, count); - _mav_put_uint8_t(buf, 18, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#else - mavlink_rally_point_t packet; - packet.lat = lat; - packet.lng = lng; - packet.alt = alt; - packet.break_alt = break_alt; - packet.land_dir = land_dir; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - packet.count = count; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RALLY_POINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#endif -} - -/** - * @brief Pack a rally_point message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 0) - * @param count total number of points (for sanity checking) - * @param lat Latitude of point in degrees * 1E7 - * @param lng Longitude of point in degrees * 1E7 - * @param alt Transit / loiter altitude in meters relative to home - * @param break_alt Break altitude in meters relative to home - * @param land_dir Heading to aim for when landing. In centi-degrees. - * @param flags See RALLY_FLAGS enum for definition of the bitmask. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rally_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t idx,uint8_t count,int32_t lat,int32_t lng,int16_t alt,int16_t break_alt,uint16_t land_dir,uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lng); - _mav_put_int16_t(buf, 8, alt); - _mav_put_int16_t(buf, 10, break_alt); - _mav_put_uint16_t(buf, 12, land_dir); - _mav_put_uint8_t(buf, 14, target_system); - _mav_put_uint8_t(buf, 15, target_component); - _mav_put_uint8_t(buf, 16, idx); - _mav_put_uint8_t(buf, 17, count); - _mav_put_uint8_t(buf, 18, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#else - mavlink_rally_point_t packet; - packet.lat = lat; - packet.lng = lng; - packet.alt = alt; - packet.break_alt = break_alt; - packet.land_dir = land_dir; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - packet.count = count; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RALLY_POINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#endif -} - -/** - * @brief Encode a rally_point struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rally_point C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rally_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rally_point_t* rally_point) -{ - return mavlink_msg_rally_point_pack(system_id, component_id, msg, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags); -} - -/** - * @brief Encode a rally_point struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rally_point C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rally_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rally_point_t* rally_point) -{ - return mavlink_msg_rally_point_pack_chan(system_id, component_id, chan, msg, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags); -} - -/** - * @brief Send a rally_point message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param idx point index (first point is 0) - * @param count total number of points (for sanity checking) - * @param lat Latitude of point in degrees * 1E7 - * @param lng Longitude of point in degrees * 1E7 - * @param alt Transit / loiter altitude in meters relative to home - * @param break_alt Break altitude in meters relative to home - * @param land_dir Heading to aim for when landing. In centi-degrees. - * @param flags See RALLY_FLAGS enum for definition of the bitmask. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rally_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN]; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lng); - _mav_put_int16_t(buf, 8, alt); - _mav_put_int16_t(buf, 10, break_alt); - _mav_put_uint16_t(buf, 12, land_dir); - _mav_put_uint8_t(buf, 14, target_system); - _mav_put_uint8_t(buf, 15, target_component); - _mav_put_uint8_t(buf, 16, idx); - _mav_put_uint8_t(buf, 17, count); - _mav_put_uint8_t(buf, 18, flags); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#endif -#else - mavlink_rally_point_t packet; - packet.lat = lat; - packet.lng = lng; - packet.alt = alt; - packet.break_alt = break_alt; - packet.land_dir = land_dir; - packet.target_system = target_system; - packet.target_component = target_component; - packet.idx = idx; - packet.count = count; - packet.flags = flags; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RALLY_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rally_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lat); - _mav_put_int32_t(buf, 4, lng); - _mav_put_int16_t(buf, 8, alt); - _mav_put_int16_t(buf, 10, break_alt); - _mav_put_uint16_t(buf, 12, land_dir); - _mav_put_uint8_t(buf, 14, target_system); - _mav_put_uint8_t(buf, 15, target_component); - _mav_put_uint8_t(buf, 16, idx); - _mav_put_uint8_t(buf, 17, count); - _mav_put_uint8_t(buf, 18, flags); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#endif -#else - mavlink_rally_point_t *packet = (mavlink_rally_point_t *)msgbuf; - packet->lat = lat; - packet->lng = lng; - packet->alt = alt; - packet->break_alt = break_alt; - packet->land_dir = land_dir; - packet->target_system = target_system; - packet->target_component = target_component; - packet->idx = idx; - packet->count = count; - packet->flags = flags; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_POINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RALLY_POINT UNPACKING - - -/** - * @brief Get field target_system from rally_point message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_rally_point_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Get field target_component from rally_point message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_rally_point_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 15); -} - -/** - * @brief Get field idx from rally_point message - * - * @return point index (first point is 0) - */ -static inline uint8_t mavlink_msg_rally_point_get_idx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field count from rally_point message - * - * @return total number of points (for sanity checking) - */ -static inline uint8_t mavlink_msg_rally_point_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field lat from rally_point message - * - * @return Latitude of point in degrees * 1E7 - */ -static inline int32_t mavlink_msg_rally_point_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lng from rally_point message - * - * @return Longitude of point in degrees * 1E7 - */ -static inline int32_t mavlink_msg_rally_point_get_lng(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field alt from rally_point message - * - * @return Transit / loiter altitude in meters relative to home - */ -static inline int16_t mavlink_msg_rally_point_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field break_alt from rally_point message - * - * @return Break altitude in meters relative to home - */ -static inline int16_t mavlink_msg_rally_point_get_break_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field land_dir from rally_point message - * - * @return Heading to aim for when landing. In centi-degrees. - */ -static inline uint16_t mavlink_msg_rally_point_get_land_dir(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field flags from rally_point message - * - * @return See RALLY_FLAGS enum for definition of the bitmask. - */ -static inline uint8_t mavlink_msg_rally_point_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Decode a rally_point message into a struct - * - * @param msg The message to decode - * @param rally_point C-struct to decode the message contents into - */ -static inline void mavlink_msg_rally_point_decode(const mavlink_message_t* msg, mavlink_rally_point_t* rally_point) -{ -#if MAVLINK_NEED_BYTE_SWAP - rally_point->lat = mavlink_msg_rally_point_get_lat(msg); - rally_point->lng = mavlink_msg_rally_point_get_lng(msg); - rally_point->alt = mavlink_msg_rally_point_get_alt(msg); - rally_point->break_alt = mavlink_msg_rally_point_get_break_alt(msg); - rally_point->land_dir = mavlink_msg_rally_point_get_land_dir(msg); - rally_point->target_system = mavlink_msg_rally_point_get_target_system(msg); - rally_point->target_component = mavlink_msg_rally_point_get_target_component(msg); - rally_point->idx = mavlink_msg_rally_point_get_idx(msg); - rally_point->count = mavlink_msg_rally_point_get_count(msg); - rally_point->flags = mavlink_msg_rally_point_get_flags(msg); -#else - memcpy(rally_point, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RALLY_POINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h deleted file mode 100644 index 464ce8a47..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_rangefinder.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE RANGEFINDER PACKING - -#define MAVLINK_MSG_ID_RANGEFINDER 173 - -typedef struct __mavlink_rangefinder_t -{ - float distance; ///< distance in meters - float voltage; ///< raw voltage if available, zero otherwise -} mavlink_rangefinder_t; - -#define MAVLINK_MSG_ID_RANGEFINDER_LEN 8 -#define MAVLINK_MSG_ID_173_LEN 8 - -#define MAVLINK_MSG_ID_RANGEFINDER_CRC 83 -#define MAVLINK_MSG_ID_173_CRC 83 - - - -#define MAVLINK_MESSAGE_INFO_RANGEFINDER { \ - "RANGEFINDER", \ - 2, \ - { { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rangefinder_t, distance) }, \ - { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rangefinder_t, voltage) }, \ - } \ -} - - -/** - * @brief Pack a rangefinder message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param distance distance in meters - * @param voltage raw voltage if available, zero otherwise - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rangefinder_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float distance, float voltage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN]; - _mav_put_float(buf, 0, distance); - _mav_put_float(buf, 4, voltage); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#else - mavlink_rangefinder_t packet; - packet.distance = distance; - packet.voltage = voltage; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RANGEFINDER; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#endif -} - -/** - * @brief Pack a rangefinder message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param distance distance in meters - * @param voltage raw voltage if available, zero otherwise - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rangefinder_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float distance,float voltage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN]; - _mav_put_float(buf, 0, distance); - _mav_put_float(buf, 4, voltage); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#else - mavlink_rangefinder_t packet; - packet.distance = distance; - packet.voltage = voltage; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RANGEFINDER; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#endif -} - -/** - * @brief Encode a rangefinder struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rangefinder C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rangefinder_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder) -{ - return mavlink_msg_rangefinder_pack(system_id, component_id, msg, rangefinder->distance, rangefinder->voltage); -} - -/** - * @brief Encode a rangefinder struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rangefinder C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rangefinder_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder) -{ - return mavlink_msg_rangefinder_pack_chan(system_id, component_id, chan, msg, rangefinder->distance, rangefinder->voltage); -} - -/** - * @brief Send a rangefinder message - * @param chan MAVLink channel to send the message - * - * @param distance distance in meters - * @param voltage raw voltage if available, zero otherwise - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rangefinder_send(mavlink_channel_t chan, float distance, float voltage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN]; - _mav_put_float(buf, 0, distance); - _mav_put_float(buf, 4, voltage); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#endif -#else - mavlink_rangefinder_t packet; - packet.distance = distance; - packet.voltage = voltage; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)&packet, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)&packet, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RANGEFINDER_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rangefinder_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float distance, float voltage) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, distance); - _mav_put_float(buf, 4, voltage); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#endif -#else - mavlink_rangefinder_t *packet = (mavlink_rangefinder_t *)msgbuf; - packet->distance = distance; - packet->voltage = voltage; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)packet, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)packet, MAVLINK_MSG_ID_RANGEFINDER_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RANGEFINDER UNPACKING - - -/** - * @brief Get field distance from rangefinder message - * - * @return distance in meters - */ -static inline float mavlink_msg_rangefinder_get_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field voltage from rangefinder message - * - * @return raw voltage if available, zero otherwise - */ -static inline float mavlink_msg_rangefinder_get_voltage(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a rangefinder message into a struct - * - * @param msg The message to decode - * @param rangefinder C-struct to decode the message contents into - */ -static inline void mavlink_msg_rangefinder_decode(const mavlink_message_t* msg, mavlink_rangefinder_t* rangefinder) -{ -#if MAVLINK_NEED_BYTE_SWAP - rangefinder->distance = mavlink_msg_rangefinder_get_distance(msg); - rangefinder->voltage = mavlink_msg_rangefinder_get_voltage(msg); -#else - memcpy(rangefinder, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RANGEFINDER_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h deleted file mode 100644 index d18f31c95..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h +++ /dev/null @@ -1,473 +0,0 @@ -// MESSAGE SENSOR_OFFSETS PACKING - -#define MAVLINK_MSG_ID_SENSOR_OFFSETS 150 - -typedef struct __mavlink_sensor_offsets_t -{ - float mag_declination; ///< magnetic declination (radians) - int32_t raw_press; ///< raw pressure from barometer - int32_t raw_temp; ///< raw temperature from barometer - float gyro_cal_x; ///< gyro X calibration - float gyro_cal_y; ///< gyro Y calibration - float gyro_cal_z; ///< gyro Z calibration - float accel_cal_x; ///< accel X calibration - float accel_cal_y; ///< accel Y calibration - float accel_cal_z; ///< accel Z calibration - int16_t mag_ofs_x; ///< magnetometer X offset - int16_t mag_ofs_y; ///< magnetometer Y offset - int16_t mag_ofs_z; ///< magnetometer Z offset -} mavlink_sensor_offsets_t; - -#define MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN 42 -#define MAVLINK_MSG_ID_150_LEN 42 - -#define MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC 134 -#define MAVLINK_MSG_ID_150_CRC 134 - - - -#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \ - "SENSOR_OFFSETS", \ - 12, \ - { { "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \ - { "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \ - { "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \ - { "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \ - { "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \ - { "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \ - { "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \ - { "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \ - { "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \ - { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \ - { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \ - { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \ - } \ -} - - -/** - * @brief Pack a sensor_offsets message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param mag_ofs_x magnetometer X offset - * @param mag_ofs_y magnetometer Y offset - * @param mag_ofs_z magnetometer Z offset - * @param mag_declination magnetic declination (radians) - * @param raw_press raw pressure from barometer - * @param raw_temp raw temperature from barometer - * @param gyro_cal_x gyro X calibration - * @param gyro_cal_y gyro Y calibration - * @param gyro_cal_z gyro Z calibration - * @param accel_cal_x accel X calibration - * @param accel_cal_y accel Y calibration - * @param accel_cal_z accel Z calibration - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN]; - _mav_put_float(buf, 0, mag_declination); - _mav_put_int32_t(buf, 4, raw_press); - _mav_put_int32_t(buf, 8, raw_temp); - _mav_put_float(buf, 12, gyro_cal_x); - _mav_put_float(buf, 16, gyro_cal_y); - _mav_put_float(buf, 20, gyro_cal_z); - _mav_put_float(buf, 24, accel_cal_x); - _mav_put_float(buf, 28, accel_cal_y); - _mav_put_float(buf, 32, accel_cal_z); - _mav_put_int16_t(buf, 36, mag_ofs_x); - _mav_put_int16_t(buf, 38, mag_ofs_y); - _mav_put_int16_t(buf, 40, mag_ofs_z); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#else - mavlink_sensor_offsets_t packet; - packet.mag_declination = mag_declination; - packet.raw_press = raw_press; - packet.raw_temp = raw_temp; - packet.gyro_cal_x = gyro_cal_x; - packet.gyro_cal_y = gyro_cal_y; - packet.gyro_cal_z = gyro_cal_z; - packet.accel_cal_x = accel_cal_x; - packet.accel_cal_y = accel_cal_y; - packet.accel_cal_z = accel_cal_z; - packet.mag_ofs_x = mag_ofs_x; - packet.mag_ofs_y = mag_ofs_y; - packet.mag_ofs_z = mag_ofs_z; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#endif -} - -/** - * @brief Pack a sensor_offsets message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mag_ofs_x magnetometer X offset - * @param mag_ofs_y magnetometer Y offset - * @param mag_ofs_z magnetometer Z offset - * @param mag_declination magnetic declination (radians) - * @param raw_press raw pressure from barometer - * @param raw_temp raw temperature from barometer - * @param gyro_cal_x gyro X calibration - * @param gyro_cal_y gyro Y calibration - * @param gyro_cal_z gyro Z calibration - * @param accel_cal_x accel X calibration - * @param accel_cal_y accel Y calibration - * @param accel_cal_z accel Z calibration - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z,float mag_declination,int32_t raw_press,int32_t raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN]; - _mav_put_float(buf, 0, mag_declination); - _mav_put_int32_t(buf, 4, raw_press); - _mav_put_int32_t(buf, 8, raw_temp); - _mav_put_float(buf, 12, gyro_cal_x); - _mav_put_float(buf, 16, gyro_cal_y); - _mav_put_float(buf, 20, gyro_cal_z); - _mav_put_float(buf, 24, accel_cal_x); - _mav_put_float(buf, 28, accel_cal_y); - _mav_put_float(buf, 32, accel_cal_z); - _mav_put_int16_t(buf, 36, mag_ofs_x); - _mav_put_int16_t(buf, 38, mag_ofs_y); - _mav_put_int16_t(buf, 40, mag_ofs_z); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#else - mavlink_sensor_offsets_t packet; - packet.mag_declination = mag_declination; - packet.raw_press = raw_press; - packet.raw_temp = raw_temp; - packet.gyro_cal_x = gyro_cal_x; - packet.gyro_cal_y = gyro_cal_y; - packet.gyro_cal_z = gyro_cal_z; - packet.accel_cal_x = accel_cal_x; - packet.accel_cal_y = accel_cal_y; - packet.accel_cal_z = accel_cal_z; - packet.mag_ofs_x = mag_ofs_x; - packet.mag_ofs_y = mag_ofs_y; - packet.mag_ofs_z = mag_ofs_z; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#endif -} - -/** - * @brief Encode a sensor_offsets struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param sensor_offsets C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets) -{ - return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z); -} - -/** - * @brief Encode a sensor_offsets struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sensor_offsets C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sensor_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets) -{ - return mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, chan, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z); -} - -/** - * @brief Send a sensor_offsets message - * @param chan MAVLink channel to send the message - * - * @param mag_ofs_x magnetometer X offset - * @param mag_ofs_y magnetometer Y offset - * @param mag_ofs_z magnetometer Z offset - * @param mag_declination magnetic declination (radians) - * @param raw_press raw pressure from barometer - * @param raw_temp raw temperature from barometer - * @param gyro_cal_x gyro X calibration - * @param gyro_cal_y gyro Y calibration - * @param gyro_cal_z gyro Z calibration - * @param accel_cal_x accel X calibration - * @param accel_cal_y accel Y calibration - * @param accel_cal_z accel Z calibration - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN]; - _mav_put_float(buf, 0, mag_declination); - _mav_put_int32_t(buf, 4, raw_press); - _mav_put_int32_t(buf, 8, raw_temp); - _mav_put_float(buf, 12, gyro_cal_x); - _mav_put_float(buf, 16, gyro_cal_y); - _mav_put_float(buf, 20, gyro_cal_z); - _mav_put_float(buf, 24, accel_cal_x); - _mav_put_float(buf, 28, accel_cal_y); - _mav_put_float(buf, 32, accel_cal_z); - _mav_put_int16_t(buf, 36, mag_ofs_x); - _mav_put_int16_t(buf, 38, mag_ofs_y); - _mav_put_int16_t(buf, 40, mag_ofs_z); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#endif -#else - mavlink_sensor_offsets_t packet; - packet.mag_declination = mag_declination; - packet.raw_press = raw_press; - packet.raw_temp = raw_temp; - packet.gyro_cal_x = gyro_cal_x; - packet.gyro_cal_y = gyro_cal_y; - packet.gyro_cal_z = gyro_cal_z; - packet.accel_cal_x = accel_cal_x; - packet.accel_cal_y = accel_cal_y; - packet.accel_cal_z = accel_cal_z; - packet.mag_ofs_x = mag_ofs_x; - packet.mag_ofs_y = mag_ofs_y; - packet.mag_ofs_z = mag_ofs_z; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sensor_offsets_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, mag_declination); - _mav_put_int32_t(buf, 4, raw_press); - _mav_put_int32_t(buf, 8, raw_temp); - _mav_put_float(buf, 12, gyro_cal_x); - _mav_put_float(buf, 16, gyro_cal_y); - _mav_put_float(buf, 20, gyro_cal_z); - _mav_put_float(buf, 24, accel_cal_x); - _mav_put_float(buf, 28, accel_cal_y); - _mav_put_float(buf, 32, accel_cal_z); - _mav_put_int16_t(buf, 36, mag_ofs_x); - _mav_put_int16_t(buf, 38, mag_ofs_y); - _mav_put_int16_t(buf, 40, mag_ofs_z); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#endif -#else - mavlink_sensor_offsets_t *packet = (mavlink_sensor_offsets_t *)msgbuf; - packet->mag_declination = mag_declination; - packet->raw_press = raw_press; - packet->raw_temp = raw_temp; - packet->gyro_cal_x = gyro_cal_x; - packet->gyro_cal_y = gyro_cal_y; - packet->gyro_cal_z = gyro_cal_z; - packet->accel_cal_x = accel_cal_x; - packet->accel_cal_y = accel_cal_y; - packet->accel_cal_z = accel_cal_z; - packet->mag_ofs_x = mag_ofs_x; - packet->mag_ofs_y = mag_ofs_y; - packet->mag_ofs_z = mag_ofs_z; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SENSOR_OFFSETS UNPACKING - - -/** - * @brief Get field mag_ofs_x from sensor_offsets message - * - * @return magnetometer X offset - */ -static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 36); -} - -/** - * @brief Get field mag_ofs_y from sensor_offsets message - * - * @return magnetometer Y offset - */ -static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 38); -} - -/** - * @brief Get field mag_ofs_z from sensor_offsets message - * - * @return magnetometer Z offset - */ -static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field mag_declination from sensor_offsets message - * - * @return magnetic declination (radians) - */ -static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field raw_press from sensor_offsets message - * - * @return raw pressure from barometer - */ -static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field raw_temp from sensor_offsets message - * - * @return raw temperature from barometer - */ -static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field gyro_cal_x from sensor_offsets message - * - * @return gyro X calibration - */ -static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field gyro_cal_y from sensor_offsets message - * - * @return gyro Y calibration - */ -static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field gyro_cal_z from sensor_offsets message - * - * @return gyro Z calibration - */ -static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field accel_cal_x from sensor_offsets message - * - * @return accel X calibration - */ -static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field accel_cal_y from sensor_offsets message - * - * @return accel Y calibration - */ -static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field accel_cal_z from sensor_offsets message - * - * @return accel Z calibration - */ -static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Decode a sensor_offsets message into a struct - * - * @param msg The message to decode - * @param sensor_offsets C-struct to decode the message contents into - */ -static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets) -{ -#if MAVLINK_NEED_BYTE_SWAP - sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg); - sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg); - sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg); - sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg); - sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg); - sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg); - sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg); - sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg); - sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg); - sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg); - sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg); - sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg); -#else - memcpy(sensor_offsets, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h deleted file mode 100644 index fc6aa71e0..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE SET_MAG_OFFSETS PACKING - -#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151 - -typedef struct __mavlink_set_mag_offsets_t -{ - int16_t mag_ofs_x; ///< magnetometer X offset - int16_t mag_ofs_y; ///< magnetometer Y offset - int16_t mag_ofs_z; ///< magnetometer Z offset - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_set_mag_offsets_t; - -#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8 -#define MAVLINK_MSG_ID_151_LEN 8 - -#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC 219 -#define MAVLINK_MSG_ID_151_CRC 219 - - - -#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \ - "SET_MAG_OFFSETS", \ - 5, \ - { { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \ - { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \ - { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a set_mag_offsets message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param mag_ofs_x magnetometer X offset - * @param mag_ofs_y magnetometer Y offset - * @param mag_ofs_z magnetometer Z offset - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN]; - _mav_put_int16_t(buf, 0, mag_ofs_x); - _mav_put_int16_t(buf, 2, mag_ofs_y); - _mav_put_int16_t(buf, 4, mag_ofs_z); - _mav_put_uint8_t(buf, 6, target_system); - _mav_put_uint8_t(buf, 7, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#else - mavlink_set_mag_offsets_t packet; - packet.mag_ofs_x = mag_ofs_x; - packet.mag_ofs_y = mag_ofs_y; - packet.mag_ofs_z = mag_ofs_z; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#endif -} - -/** - * @brief Pack a set_mag_offsets message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param mag_ofs_x magnetometer X offset - * @param mag_ofs_y magnetometer Y offset - * @param mag_ofs_z magnetometer Z offset - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN]; - _mav_put_int16_t(buf, 0, mag_ofs_x); - _mav_put_int16_t(buf, 2, mag_ofs_y); - _mav_put_int16_t(buf, 4, mag_ofs_z); - _mav_put_uint8_t(buf, 6, target_system); - _mav_put_uint8_t(buf, 7, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#else - mavlink_set_mag_offsets_t packet; - packet.mag_ofs_x = mag_ofs_x; - packet.mag_ofs_y = mag_ofs_y; - packet.mag_ofs_z = mag_ofs_z; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#endif -} - -/** - * @brief Encode a set_mag_offsets struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_mag_offsets C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets) -{ - return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z); -} - -/** - * @brief Encode a set_mag_offsets struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_mag_offsets C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mag_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets) -{ - return mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, chan, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z); -} - -/** - * @brief Send a set_mag_offsets message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param mag_ofs_x magnetometer X offset - * @param mag_ofs_y magnetometer Y offset - * @param mag_ofs_z magnetometer Z offset - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN]; - _mav_put_int16_t(buf, 0, mag_ofs_x); - _mav_put_int16_t(buf, 2, mag_ofs_y); - _mav_put_int16_t(buf, 4, mag_ofs_z); - _mav_put_uint8_t(buf, 6, target_system); - _mav_put_uint8_t(buf, 7, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#endif -#else - mavlink_set_mag_offsets_t packet; - packet.mag_ofs_x = mag_ofs_x; - packet.mag_ofs_y = mag_ofs_y; - packet.mag_ofs_z = mag_ofs_z; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_mag_offsets_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, mag_ofs_x); - _mav_put_int16_t(buf, 2, mag_ofs_y); - _mav_put_int16_t(buf, 4, mag_ofs_z); - _mav_put_uint8_t(buf, 6, target_system); - _mav_put_uint8_t(buf, 7, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#endif -#else - mavlink_set_mag_offsets_t *packet = (mavlink_set_mag_offsets_t *)msgbuf; - packet->mag_ofs_x = mag_ofs_x; - packet->mag_ofs_y = mag_ofs_y; - packet->mag_ofs_z = mag_ofs_z; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_MAG_OFFSETS UNPACKING - - -/** - * @brief Get field target_system from set_mag_offsets message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field target_component from set_mag_offsets message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field mag_ofs_x from set_mag_offsets message - * - * @return magnetometer X offset - */ -static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field mag_ofs_y from set_mag_offsets message - * - * @return magnetometer Y offset - */ -static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Get field mag_ofs_z from set_mag_offsets message - * - * @return magnetometer Z offset - */ -static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Decode a set_mag_offsets message into a struct - * - * @param msg The message to decode - * @param set_mag_offsets C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg); - set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg); - set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg); - set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg); - set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg); -#else - memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h deleted file mode 100644 index 48cfb6ffd..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h +++ /dev/null @@ -1,449 +0,0 @@ -// MESSAGE SIMSTATE PACKING - -#define MAVLINK_MSG_ID_SIMSTATE 164 - -typedef struct __mavlink_simstate_t -{ - float roll; ///< Roll angle (rad) - float pitch; ///< Pitch angle (rad) - float yaw; ///< Yaw angle (rad) - float xacc; ///< X acceleration m/s/s - float yacc; ///< Y acceleration m/s/s - float zacc; ///< Z acceleration m/s/s - float xgyro; ///< Angular speed around X axis rad/s - float ygyro; ///< Angular speed around Y axis rad/s - float zgyro; ///< Angular speed around Z axis rad/s - int32_t lat; ///< Latitude in degrees * 1E7 - int32_t lng; ///< Longitude in degrees * 1E7 -} mavlink_simstate_t; - -#define MAVLINK_MSG_ID_SIMSTATE_LEN 44 -#define MAVLINK_MSG_ID_164_LEN 44 - -#define MAVLINK_MSG_ID_SIMSTATE_CRC 154 -#define MAVLINK_MSG_ID_164_CRC 154 - - - -#define MAVLINK_MESSAGE_INFO_SIMSTATE { \ - "SIMSTATE", \ - 11, \ - { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_simstate_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_simstate_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_simstate_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_simstate_t, lat) }, \ - { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_simstate_t, lng) }, \ - } \ -} - - -/** - * @brief Pack a simstate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees * 1E7 - * @param lng Longitude in degrees * 1E7 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIMSTATE_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, xacc); - _mav_put_float(buf, 16, yacc); - _mav_put_float(buf, 20, zacc); - _mav_put_float(buf, 24, xgyro); - _mav_put_float(buf, 28, ygyro); - _mav_put_float(buf, 32, zgyro); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lng); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN); -#else - mavlink_simstate_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.lat = lat; - packet.lng = lng; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIMSTATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIMSTATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIMSTATE_LEN); -#endif -} - -/** - * @brief Pack a simstate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees * 1E7 - * @param lng Longitude in degrees * 1E7 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,int32_t lat,int32_t lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIMSTATE_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, xacc); - _mav_put_float(buf, 16, yacc); - _mav_put_float(buf, 20, zacc); - _mav_put_float(buf, 24, xgyro); - _mav_put_float(buf, 28, ygyro); - _mav_put_float(buf, 32, zgyro); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lng); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN); -#else - mavlink_simstate_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.lat = lat; - packet.lng = lng; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIMSTATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIMSTATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIMSTATE_LEN); -#endif -} - -/** - * @brief Encode a simstate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param simstate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_simstate_t* simstate) -{ - return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng); -} - -/** - * @brief Encode a simstate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param simstate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_simstate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_simstate_t* simstate) -{ - return mavlink_msg_simstate_pack_chan(system_id, component_id, chan, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng); -} - -/** - * @brief Send a simstate message - * @param chan MAVLink channel to send the message - * - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees * 1E7 - * @param lng Longitude in degrees * 1E7 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIMSTATE_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, xacc); - _mav_put_float(buf, 16, yacc); - _mav_put_float(buf, 20, zacc); - _mav_put_float(buf, 24, xgyro); - _mav_put_float(buf, 28, ygyro); - _mav_put_float(buf, 32, zgyro); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lng); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_LEN); -#endif -#else - mavlink_simstate_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.lat = lat; - packet.lng = lng; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, MAVLINK_MSG_ID_SIMSTATE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SIMSTATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_simstate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, xacc); - _mav_put_float(buf, 16, yacc); - _mav_put_float(buf, 20, zacc); - _mav_put_float(buf, 24, xgyro); - _mav_put_float(buf, 28, ygyro); - _mav_put_float(buf, 32, zgyro); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lng); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_LEN); -#endif -#else - mavlink_simstate_t *packet = (mavlink_simstate_t *)msgbuf; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->lat = lat; - packet->lng = lng; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)packet, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)packet, MAVLINK_MSG_ID_SIMSTATE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SIMSTATE UNPACKING - - -/** - * @brief Get field roll from simstate message - * - * @return Roll angle (rad) - */ -static inline float mavlink_msg_simstate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field pitch from simstate message - * - * @return Pitch angle (rad) - */ -static inline float mavlink_msg_simstate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field yaw from simstate message - * - * @return Yaw angle (rad) - */ -static inline float mavlink_msg_simstate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field xacc from simstate message - * - * @return X acceleration m/s/s - */ -static inline float mavlink_msg_simstate_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yacc from simstate message - * - * @return Y acceleration m/s/s - */ -static inline float mavlink_msg_simstate_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field zacc from simstate message - * - * @return Z acceleration m/s/s - */ -static inline float mavlink_msg_simstate_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field xgyro from simstate message - * - * @return Angular speed around X axis rad/s - */ -static inline float mavlink_msg_simstate_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field ygyro from simstate message - * - * @return Angular speed around Y axis rad/s - */ -static inline float mavlink_msg_simstate_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field zgyro from simstate message - * - * @return Angular speed around Z axis rad/s - */ -static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field lat from simstate message - * - * @return Latitude in degrees * 1E7 - */ -static inline int32_t mavlink_msg_simstate_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field lng from simstate message - * - * @return Longitude in degrees * 1E7 - */ -static inline int32_t mavlink_msg_simstate_get_lng(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 40); -} - -/** - * @brief Decode a simstate message into a struct - * - * @param msg The message to decode - * @param simstate C-struct to decode the message contents into - */ -static inline void mavlink_msg_simstate_decode(const mavlink_message_t* msg, mavlink_simstate_t* simstate) -{ -#if MAVLINK_NEED_BYTE_SWAP - simstate->roll = mavlink_msg_simstate_get_roll(msg); - simstate->pitch = mavlink_msg_simstate_get_pitch(msg); - simstate->yaw = mavlink_msg_simstate_get_yaw(msg); - simstate->xacc = mavlink_msg_simstate_get_xacc(msg); - simstate->yacc = mavlink_msg_simstate_get_yacc(msg); - simstate->zacc = mavlink_msg_simstate_get_zacc(msg); - simstate->xgyro = mavlink_msg_simstate_get_xgyro(msg); - simstate->ygyro = mavlink_msg_simstate_get_ygyro(msg); - simstate->zgyro = mavlink_msg_simstate_get_zgyro(msg); - simstate->lat = mavlink_msg_simstate_get_lat(msg); - simstate->lng = mavlink_msg_simstate_get_lng(msg); -#else - memcpy(simstate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SIMSTATE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h b/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h deleted file mode 100644 index 5d5edc4cc..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_wind.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE WIND PACKING - -#define MAVLINK_MSG_ID_WIND 168 - -typedef struct __mavlink_wind_t -{ - float direction; ///< wind direction that wind is coming from (degrees) - float speed; ///< wind speed in ground plane (m/s) - float speed_z; ///< vertical wind speed (m/s) -} mavlink_wind_t; - -#define MAVLINK_MSG_ID_WIND_LEN 12 -#define MAVLINK_MSG_ID_168_LEN 12 - -#define MAVLINK_MSG_ID_WIND_CRC 1 -#define MAVLINK_MSG_ID_168_CRC 1 - - - -#define MAVLINK_MESSAGE_INFO_WIND { \ - "WIND", \ - 3, \ - { { "direction", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_wind_t, direction) }, \ - { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_wind_t, speed) }, \ - { "speed_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_t, speed_z) }, \ - } \ -} - - -/** - * @brief Pack a wind message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param direction wind direction that wind is coming from (degrees) - * @param speed wind speed in ground plane (m/s) - * @param speed_z vertical wind speed (m/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float direction, float speed, float speed_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_LEN]; - _mav_put_float(buf, 0, direction); - _mav_put_float(buf, 4, speed); - _mav_put_float(buf, 8, speed_z); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN); -#else - mavlink_wind_t packet; - packet.direction = direction; - packet.speed = speed; - packet.speed_z = speed_z; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIND; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_LEN); -#endif -} - -/** - * @brief Pack a wind message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param direction wind direction that wind is coming from (degrees) - * @param speed wind speed in ground plane (m/s) - * @param speed_z vertical wind speed (m/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float direction,float speed,float speed_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_LEN]; - _mav_put_float(buf, 0, direction); - _mav_put_float(buf, 4, speed); - _mav_put_float(buf, 8, speed_z); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN); -#else - mavlink_wind_t packet; - packet.direction = direction; - packet.speed = speed; - packet.speed_z = speed_z; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WIND; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_LEN); -#endif -} - -/** - * @brief Encode a wind struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param wind C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wind_t* wind) -{ - return mavlink_msg_wind_pack(system_id, component_id, msg, wind->direction, wind->speed, wind->speed_z); -} - -/** - * @brief Encode a wind struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param wind C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_wind_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_t* wind) -{ - return mavlink_msg_wind_pack_chan(system_id, component_id, chan, msg, wind->direction, wind->speed, wind->speed_z); -} - -/** - * @brief Send a wind message - * @param chan MAVLink channel to send the message - * - * @param direction wind direction that wind is coming from (degrees) - * @param speed wind speed in ground plane (m/s) - * @param speed_z vertical wind speed (m/s) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_wind_send(mavlink_channel_t chan, float direction, float speed, float speed_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WIND_LEN]; - _mav_put_float(buf, 0, direction); - _mav_put_float(buf, 4, speed); - _mav_put_float(buf, 8, speed_z); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_LEN); -#endif -#else - mavlink_wind_t packet; - packet.direction = direction; - packet.speed = speed; - packet.speed_z = speed_z; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)&packet, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)&packet, MAVLINK_MSG_ID_WIND_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_WIND_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_wind_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float direction, float speed, float speed_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, direction); - _mav_put_float(buf, 4, speed); - _mav_put_float(buf, 8, speed_z); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_LEN); -#endif -#else - mavlink_wind_t *packet = (mavlink_wind_t *)msgbuf; - packet->direction = direction; - packet->speed = speed; - packet->speed_z = speed_z; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)packet, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)packet, MAVLINK_MSG_ID_WIND_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE WIND UNPACKING - - -/** - * @brief Get field direction from wind message - * - * @return wind direction that wind is coming from (degrees) - */ -static inline float mavlink_msg_wind_get_direction(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field speed from wind message - * - * @return wind speed in ground plane (m/s) - */ -static inline float mavlink_msg_wind_get_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field speed_z from wind message - * - * @return vertical wind speed (m/s) - */ -static inline float mavlink_msg_wind_get_speed_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Decode a wind message into a struct - * - * @param msg The message to decode - * @param wind C-struct to decode the message contents into - */ -static inline void mavlink_msg_wind_decode(const mavlink_message_t* msg, mavlink_wind_t* wind) -{ -#if MAVLINK_NEED_BYTE_SWAP - wind->direction = mavlink_msg_wind_get_direction(msg); - wind->speed = mavlink_msg_wind_get_speed(msg); - wind->speed_z = mavlink_msg_wind_get_speed_z(msg); -#else - memcpy(wind, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WIND_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h b/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h deleted file mode 100644 index 489553ea4..000000000 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/testsuite.h +++ /dev/null @@ -1,1542 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from ardupilotmega.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef ARDUPILOTMEGA_TESTSUITE_H -#define ARDUPILOTMEGA_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); -static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_test_common(system_id, component_id, last_msg); - mavlink_test_ardupilotmega(system_id, component_id, last_msg); -} -#endif - -#include "../common/testsuite.h" - - -static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_sensor_offsets_t packet_in = { - 17.0, - }963497672, - }963497880, - }101.0, - }129.0, - }157.0, - }185.0, - }213.0, - }241.0, - }19107, - }19211, - }19315, - }; - mavlink_sensor_offsets_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.mag_declination = packet_in.mag_declination; - packet1.raw_press = packet_in.raw_press; - packet1.raw_temp = packet_in.raw_temp; - packet1.gyro_cal_x = packet_in.gyro_cal_x; - packet1.gyro_cal_y = packet_in.gyro_cal_y; - packet1.gyro_cal_z = packet_in.gyro_cal_z; - packet1.accel_cal_x = packet_in.accel_cal_x; - packet1.accel_cal_y = packet_in.accel_cal_y; - packet1.accel_cal_z = packet_in.accel_cal_z; - packet1.mag_ofs_x = packet_in.mag_ofs_x; - packet1.mag_ofs_y = packet_in.mag_ofs_y; - packet1.mag_ofs_z = packet_in.mag_ofs_z; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sensor_offsets_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_sensor_offsets_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sensor_offsets_pack(system_id, component_id, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z ); - mavlink_msg_sensor_offsets_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z ); - mavlink_msg_sensor_offsets_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; i 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* 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. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - 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_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 sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ - MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ - MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ - MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */ - 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| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - 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| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ - MAV_CMD_ENUM_END=501, /* | */ -}; -#endif - -#include "../common/common.h" - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_aq_telemetry_f.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // AUTOQUAD_H diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink.h deleted file mode 100644 index 3f80c9a41..000000000 --- a/mavlink/include/mavlink/v1.0/autoquad/mavlink.h +++ /dev/null @@ -1,27 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from autoquad.xml - * @see http://pixhawk.ethz.ch/software/mavlink - */ -#ifndef MAVLINK_H -#define MAVLINK_H - -#ifndef MAVLINK_STX -#define MAVLINK_STX 254 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#include "version.h" -#include "autoquad.h" - -#endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h b/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h deleted file mode 100644 index e78d5687a..000000000 --- a/mavlink/include/mavlink/v1.0/autoquad/mavlink_msg_aq_telemetry_f.h +++ /dev/null @@ -1,689 +0,0 @@ -// MESSAGE AQ_TELEMETRY_F PACKING - -#define MAVLINK_MSG_ID_AQ_TELEMETRY_F 150 - -typedef struct __mavlink_aq_telemetry_f_t -{ - float value1; ///< value1 - float value2; ///< value2 - float value3; ///< value3 - float value4; ///< value4 - float value5; ///< value5 - float value6; ///< value6 - float value7; ///< value7 - float value8; ///< value8 - float value9; ///< value9 - float value10; ///< value10 - float value11; ///< value11 - float value12; ///< value12 - float value13; ///< value13 - float value14; ///< value14 - float value15; ///< value15 - float value16; ///< value16 - float value17; ///< value17 - float value18; ///< value18 - float value19; ///< value19 - float value20; ///< value20 - uint16_t Index; ///< Index of message -} mavlink_aq_telemetry_f_t; - -#define MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN 82 -#define MAVLINK_MSG_ID_150_LEN 82 - -#define MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC 241 -#define MAVLINK_MSG_ID_150_CRC 241 - - - -#define MAVLINK_MESSAGE_INFO_AQ_TELEMETRY_F { \ - "AQ_TELEMETRY_F", \ - 21, \ - { { "value1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_aq_telemetry_f_t, value1) }, \ - { "value2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_aq_telemetry_f_t, value2) }, \ - { "value3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aq_telemetry_f_t, value3) }, \ - { "value4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aq_telemetry_f_t, value4) }, \ - { "value5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_aq_telemetry_f_t, value5) }, \ - { "value6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_aq_telemetry_f_t, value6) }, \ - { "value7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_aq_telemetry_f_t, value7) }, \ - { "value8", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_aq_telemetry_f_t, value8) }, \ - { "value9", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_aq_telemetry_f_t, value9) }, \ - { "value10", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_aq_telemetry_f_t, value10) }, \ - { "value11", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_aq_telemetry_f_t, value11) }, \ - { "value12", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_aq_telemetry_f_t, value12) }, \ - { "value13", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_aq_telemetry_f_t, value13) }, \ - { "value14", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_aq_telemetry_f_t, value14) }, \ - { "value15", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_aq_telemetry_f_t, value15) }, \ - { "value16", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_aq_telemetry_f_t, value16) }, \ - { "value17", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_aq_telemetry_f_t, value17) }, \ - { "value18", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_aq_telemetry_f_t, value18) }, \ - { "value19", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_aq_telemetry_f_t, value19) }, \ - { "value20", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_aq_telemetry_f_t, value20) }, \ - { "Index", NULL, MAVLINK_TYPE_UINT16_T, 0, 80, offsetof(mavlink_aq_telemetry_f_t, Index) }, \ - } \ -} - - -/** - * @brief Pack a aq_telemetry_f message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param Index Index of message - * @param value1 value1 - * @param value2 value2 - * @param value3 value3 - * @param value4 value4 - * @param value5 value5 - * @param value6 value6 - * @param value7 value7 - * @param value8 value8 - * @param value9 value9 - * @param value10 value10 - * @param value11 value11 - * @param value12 value12 - * @param value13 value13 - * @param value14 value14 - * @param value15 value15 - * @param value16 value16 - * @param value17 value17 - * @param value18 value18 - * @param value19 value19 - * @param value20 value20 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_aq_telemetry_f_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN]; - _mav_put_float(buf, 0, value1); - _mav_put_float(buf, 4, value2); - _mav_put_float(buf, 8, value3); - _mav_put_float(buf, 12, value4); - _mav_put_float(buf, 16, value5); - _mav_put_float(buf, 20, value6); - _mav_put_float(buf, 24, value7); - _mav_put_float(buf, 28, value8); - _mav_put_float(buf, 32, value9); - _mav_put_float(buf, 36, value10); - _mav_put_float(buf, 40, value11); - _mav_put_float(buf, 44, value12); - _mav_put_float(buf, 48, value13); - _mav_put_float(buf, 52, value14); - _mav_put_float(buf, 56, value15); - _mav_put_float(buf, 60, value16); - _mav_put_float(buf, 64, value17); - _mav_put_float(buf, 68, value18); - _mav_put_float(buf, 72, value19); - _mav_put_float(buf, 76, value20); - _mav_put_uint16_t(buf, 80, Index); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#else - mavlink_aq_telemetry_f_t packet; - packet.value1 = value1; - packet.value2 = value2; - packet.value3 = value3; - packet.value4 = value4; - packet.value5 = value5; - packet.value6 = value6; - packet.value7 = value7; - packet.value8 = value8; - packet.value9 = value9; - packet.value10 = value10; - packet.value11 = value11; - packet.value12 = value12; - packet.value13 = value13; - packet.value14 = value14; - packet.value15 = value15; - packet.value16 = value16; - packet.value17 = value17; - packet.value18 = value18; - packet.value19 = value19; - packet.value20 = value20; - packet.Index = Index; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AQ_TELEMETRY_F; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -} - -/** - * @brief Pack a aq_telemetry_f message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param Index Index of message - * @param value1 value1 - * @param value2 value2 - * @param value3 value3 - * @param value4 value4 - * @param value5 value5 - * @param value6 value6 - * @param value7 value7 - * @param value8 value8 - * @param value9 value9 - * @param value10 value10 - * @param value11 value11 - * @param value12 value12 - * @param value13 value13 - * @param value14 value14 - * @param value15 value15 - * @param value16 value16 - * @param value17 value17 - * @param value18 value18 - * @param value19 value19 - * @param value20 value20 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_aq_telemetry_f_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t Index,float value1,float value2,float value3,float value4,float value5,float value6,float value7,float value8,float value9,float value10,float value11,float value12,float value13,float value14,float value15,float value16,float value17,float value18,float value19,float value20) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN]; - _mav_put_float(buf, 0, value1); - _mav_put_float(buf, 4, value2); - _mav_put_float(buf, 8, value3); - _mav_put_float(buf, 12, value4); - _mav_put_float(buf, 16, value5); - _mav_put_float(buf, 20, value6); - _mav_put_float(buf, 24, value7); - _mav_put_float(buf, 28, value8); - _mav_put_float(buf, 32, value9); - _mav_put_float(buf, 36, value10); - _mav_put_float(buf, 40, value11); - _mav_put_float(buf, 44, value12); - _mav_put_float(buf, 48, value13); - _mav_put_float(buf, 52, value14); - _mav_put_float(buf, 56, value15); - _mav_put_float(buf, 60, value16); - _mav_put_float(buf, 64, value17); - _mav_put_float(buf, 68, value18); - _mav_put_float(buf, 72, value19); - _mav_put_float(buf, 76, value20); - _mav_put_uint16_t(buf, 80, Index); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#else - mavlink_aq_telemetry_f_t packet; - packet.value1 = value1; - packet.value2 = value2; - packet.value3 = value3; - packet.value4 = value4; - packet.value5 = value5; - packet.value6 = value6; - packet.value7 = value7; - packet.value8 = value8; - packet.value9 = value9; - packet.value10 = value10; - packet.value11 = value11; - packet.value12 = value12; - packet.value13 = value13; - packet.value14 = value14; - packet.value15 = value15; - packet.value16 = value16; - packet.value17 = value17; - packet.value18 = value18; - packet.value19 = value19; - packet.value20 = value20; - packet.Index = Index; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AQ_TELEMETRY_F; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -} - -/** - * @brief Encode a aq_telemetry_f struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param aq_telemetry_f C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_aq_telemetry_f_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aq_telemetry_f_t* aq_telemetry_f) -{ - return mavlink_msg_aq_telemetry_f_pack(system_id, component_id, msg, aq_telemetry_f->Index, aq_telemetry_f->value1, aq_telemetry_f->value2, aq_telemetry_f->value3, aq_telemetry_f->value4, aq_telemetry_f->value5, aq_telemetry_f->value6, aq_telemetry_f->value7, aq_telemetry_f->value8, aq_telemetry_f->value9, aq_telemetry_f->value10, aq_telemetry_f->value11, aq_telemetry_f->value12, aq_telemetry_f->value13, aq_telemetry_f->value14, aq_telemetry_f->value15, aq_telemetry_f->value16, aq_telemetry_f->value17, aq_telemetry_f->value18, aq_telemetry_f->value19, aq_telemetry_f->value20); -} - -/** - * @brief Encode a aq_telemetry_f struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param aq_telemetry_f C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_aq_telemetry_f_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_aq_telemetry_f_t* aq_telemetry_f) -{ - return mavlink_msg_aq_telemetry_f_pack_chan(system_id, component_id, chan, msg, aq_telemetry_f->Index, aq_telemetry_f->value1, aq_telemetry_f->value2, aq_telemetry_f->value3, aq_telemetry_f->value4, aq_telemetry_f->value5, aq_telemetry_f->value6, aq_telemetry_f->value7, aq_telemetry_f->value8, aq_telemetry_f->value9, aq_telemetry_f->value10, aq_telemetry_f->value11, aq_telemetry_f->value12, aq_telemetry_f->value13, aq_telemetry_f->value14, aq_telemetry_f->value15, aq_telemetry_f->value16, aq_telemetry_f->value17, aq_telemetry_f->value18, aq_telemetry_f->value19, aq_telemetry_f->value20); -} - -/** - * @brief Send a aq_telemetry_f message - * @param chan MAVLink channel to send the message - * - * @param Index Index of message - * @param value1 value1 - * @param value2 value2 - * @param value3 value3 - * @param value4 value4 - * @param value5 value5 - * @param value6 value6 - * @param value7 value7 - * @param value8 value8 - * @param value9 value9 - * @param value10 value10 - * @param value11 value11 - * @param value12 value12 - * @param value13 value13 - * @param value14 value14 - * @param value15 value15 - * @param value16 value16 - * @param value17 value17 - * @param value18 value18 - * @param value19 value19 - * @param value20 value20 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_aq_telemetry_f_send(mavlink_channel_t chan, uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN]; - _mav_put_float(buf, 0, value1); - _mav_put_float(buf, 4, value2); - _mav_put_float(buf, 8, value3); - _mav_put_float(buf, 12, value4); - _mav_put_float(buf, 16, value5); - _mav_put_float(buf, 20, value6); - _mav_put_float(buf, 24, value7); - _mav_put_float(buf, 28, value8); - _mav_put_float(buf, 32, value9); - _mav_put_float(buf, 36, value10); - _mav_put_float(buf, 40, value11); - _mav_put_float(buf, 44, value12); - _mav_put_float(buf, 48, value13); - _mav_put_float(buf, 52, value14); - _mav_put_float(buf, 56, value15); - _mav_put_float(buf, 60, value16); - _mav_put_float(buf, 64, value17); - _mav_put_float(buf, 68, value18); - _mav_put_float(buf, 72, value19); - _mav_put_float(buf, 76, value20); - _mav_put_uint16_t(buf, 80, Index); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -#else - mavlink_aq_telemetry_f_t packet; - packet.value1 = value1; - packet.value2 = value2; - packet.value3 = value3; - packet.value4 = value4; - packet.value5 = value5; - packet.value6 = value6; - packet.value7 = value7; - packet.value8 = value8; - packet.value9 = value9; - packet.value10 = value10; - packet.value11 = value11; - packet.value12 = value12; - packet.value13 = value13; - packet.value14 = value14; - packet.value15 = value15; - packet.value16 = value16; - packet.value17 = value17; - packet.value18 = value18; - packet.value19 = value19; - packet.value20 = value20; - packet.Index = Index; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)&packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)&packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_aq_telemetry_f_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Index, float value1, float value2, float value3, float value4, float value5, float value6, float value7, float value8, float value9, float value10, float value11, float value12, float value13, float value14, float value15, float value16, float value17, float value18, float value19, float value20) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, value1); - _mav_put_float(buf, 4, value2); - _mav_put_float(buf, 8, value3); - _mav_put_float(buf, 12, value4); - _mav_put_float(buf, 16, value5); - _mav_put_float(buf, 20, value6); - _mav_put_float(buf, 24, value7); - _mav_put_float(buf, 28, value8); - _mav_put_float(buf, 32, value9); - _mav_put_float(buf, 36, value10); - _mav_put_float(buf, 40, value11); - _mav_put_float(buf, 44, value12); - _mav_put_float(buf, 48, value13); - _mav_put_float(buf, 52, value14); - _mav_put_float(buf, 56, value15); - _mav_put_float(buf, 60, value16); - _mav_put_float(buf, 64, value17); - _mav_put_float(buf, 68, value18); - _mav_put_float(buf, 72, value19); - _mav_put_float(buf, 76, value20); - _mav_put_uint16_t(buf, 80, Index); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, buf, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -#else - mavlink_aq_telemetry_f_t *packet = (mavlink_aq_telemetry_f_t *)msgbuf; - packet->value1 = value1; - packet->value2 = value2; - packet->value3 = value3; - packet->value4 = value4; - packet->value5 = value5; - packet->value6 = value6; - packet->value7 = value7; - packet->value8 = value8; - packet->value9 = value9; - packet->value10 = value10; - packet->value11 = value11; - packet->value12 = value12; - packet->value13 = value13; - packet->value14 = value14; - packet->value15 = value15; - packet->value16 = value16; - packet->value17 = value17; - packet->value18 = value18; - packet->value19 = value19; - packet->value20 = value20; - packet->Index = Index; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN, MAVLINK_MSG_ID_AQ_TELEMETRY_F_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AQ_TELEMETRY_F, (const char *)packet, MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE AQ_TELEMETRY_F UNPACKING - - -/** - * @brief Get field Index from aq_telemetry_f message - * - * @return Index of message - */ -static inline uint16_t mavlink_msg_aq_telemetry_f_get_Index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 80); -} - -/** - * @brief Get field value1 from aq_telemetry_f message - * - * @return value1 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field value2 from aq_telemetry_f message - * - * @return value2 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field value3 from aq_telemetry_f message - * - * @return value3 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field value4 from aq_telemetry_f message - * - * @return value4 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field value5 from aq_telemetry_f message - * - * @return value5 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field value6 from aq_telemetry_f message - * - * @return value6 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field value7 from aq_telemetry_f message - * - * @return value7 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field value8 from aq_telemetry_f message - * - * @return value8 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field value9 from aq_telemetry_f message - * - * @return value9 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value9(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field value10 from aq_telemetry_f message - * - * @return value10 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value10(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field value11 from aq_telemetry_f message - * - * @return value11 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value11(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field value12 from aq_telemetry_f message - * - * @return value12 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value12(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field value13 from aq_telemetry_f message - * - * @return value13 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value13(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field value14 from aq_telemetry_f message - * - * @return value14 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value14(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field value15 from aq_telemetry_f message - * - * @return value15 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value15(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field value16 from aq_telemetry_f message - * - * @return value16 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value16(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 60); -} - -/** - * @brief Get field value17 from aq_telemetry_f message - * - * @return value17 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value17(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 64); -} - -/** - * @brief Get field value18 from aq_telemetry_f message - * - * @return value18 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value18(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 68); -} - -/** - * @brief Get field value19 from aq_telemetry_f message - * - * @return value19 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value19(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 72); -} - -/** - * @brief Get field value20 from aq_telemetry_f message - * - * @return value20 - */ -static inline float mavlink_msg_aq_telemetry_f_get_value20(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 76); -} - -/** - * @brief Decode a aq_telemetry_f message into a struct - * - * @param msg The message to decode - * @param aq_telemetry_f C-struct to decode the message contents into - */ -static inline void mavlink_msg_aq_telemetry_f_decode(const mavlink_message_t* msg, mavlink_aq_telemetry_f_t* aq_telemetry_f) -{ -#if MAVLINK_NEED_BYTE_SWAP - aq_telemetry_f->value1 = mavlink_msg_aq_telemetry_f_get_value1(msg); - aq_telemetry_f->value2 = mavlink_msg_aq_telemetry_f_get_value2(msg); - aq_telemetry_f->value3 = mavlink_msg_aq_telemetry_f_get_value3(msg); - aq_telemetry_f->value4 = mavlink_msg_aq_telemetry_f_get_value4(msg); - aq_telemetry_f->value5 = mavlink_msg_aq_telemetry_f_get_value5(msg); - aq_telemetry_f->value6 = mavlink_msg_aq_telemetry_f_get_value6(msg); - aq_telemetry_f->value7 = mavlink_msg_aq_telemetry_f_get_value7(msg); - aq_telemetry_f->value8 = mavlink_msg_aq_telemetry_f_get_value8(msg); - aq_telemetry_f->value9 = mavlink_msg_aq_telemetry_f_get_value9(msg); - aq_telemetry_f->value10 = mavlink_msg_aq_telemetry_f_get_value10(msg); - aq_telemetry_f->value11 = mavlink_msg_aq_telemetry_f_get_value11(msg); - aq_telemetry_f->value12 = mavlink_msg_aq_telemetry_f_get_value12(msg); - aq_telemetry_f->value13 = mavlink_msg_aq_telemetry_f_get_value13(msg); - aq_telemetry_f->value14 = mavlink_msg_aq_telemetry_f_get_value14(msg); - aq_telemetry_f->value15 = mavlink_msg_aq_telemetry_f_get_value15(msg); - aq_telemetry_f->value16 = mavlink_msg_aq_telemetry_f_get_value16(msg); - aq_telemetry_f->value17 = mavlink_msg_aq_telemetry_f_get_value17(msg); - aq_telemetry_f->value18 = mavlink_msg_aq_telemetry_f_get_value18(msg); - aq_telemetry_f->value19 = mavlink_msg_aq_telemetry_f_get_value19(msg); - aq_telemetry_f->value20 = mavlink_msg_aq_telemetry_f_get_value20(msg); - aq_telemetry_f->Index = mavlink_msg_aq_telemetry_f_get_Index(msg); -#else - memcpy(aq_telemetry_f, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AQ_TELEMETRY_F_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/autoquad/testsuite.h b/mavlink/include/mavlink/v1.0/autoquad/testsuite.h deleted file mode 100644 index 4eafe7be5..000000000 --- a/mavlink/include/mavlink/v1.0/autoquad/testsuite.h +++ /dev/null @@ -1,118 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from autoquad.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef AUTOQUAD_TESTSUITE_H -#define AUTOQUAD_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); -static void mavlink_test_autoquad(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_test_common(system_id, component_id, last_msg); - mavlink_test_autoquad(system_id, component_id, last_msg); -} -#endif - -#include "../common/testsuite.h" - - -static void mavlink_test_aq_telemetry_f(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_aq_telemetry_f_t packet_in = { - 17.0, - }45.0, - }73.0, - }101.0, - }129.0, - }157.0, - }185.0, - }213.0, - }241.0, - }269.0, - }297.0, - }325.0, - }353.0, - }381.0, - }409.0, - }437.0, - }465.0, - }493.0, - }521.0, - }549.0, - }21395, - }; - mavlink_aq_telemetry_f_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.value1 = packet_in.value1; - packet1.value2 = packet_in.value2; - packet1.value3 = packet_in.value3; - packet1.value4 = packet_in.value4; - packet1.value5 = packet_in.value5; - packet1.value6 = packet_in.value6; - packet1.value7 = packet_in.value7; - packet1.value8 = packet_in.value8; - packet1.value9 = packet_in.value9; - packet1.value10 = packet_in.value10; - packet1.value11 = packet_in.value11; - packet1.value12 = packet_in.value12; - packet1.value13 = packet_in.value13; - packet1.value14 = packet_in.value14; - packet1.value15 = packet_in.value15; - packet1.value16 = packet_in.value16; - packet1.value17 = packet_in.value17; - packet1.value18 = packet_in.value18; - packet1.value19 = packet_in.value19; - packet1.value20 = packet_in.value20; - packet1.Index = packet_in.Index; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_aq_telemetry_f_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_aq_telemetry_f_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_aq_telemetry_f_pack(system_id, component_id, &msg , packet1.Index , packet1.value1 , packet1.value2 , packet1.value3 , packet1.value4 , packet1.value5 , packet1.value6 , packet1.value7 , packet1.value8 , packet1.value9 , packet1.value10 , packet1.value11 , packet1.value12 , packet1.value13 , packet1.value14 , packet1.value15 , packet1.value16 , packet1.value17 , packet1.value18 , packet1.value19 , packet1.value20 ); - mavlink_msg_aq_telemetry_f_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_aq_telemetry_f_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Index , packet1.value1 , packet1.value2 , packet1.value3 , packet1.value4 , packet1.value5 , packet1.value6 , packet1.value7 , packet1.value8 , packet1.value9 , packet1.value10 , packet1.value11 , packet1.value12 , packet1.value13 , packet1.value14 , packet1.value15 , packet1.value16 , packet1.value17 , packet1.value18 , packet1.value19 , packet1.value20 ); - mavlink_msg_aq_telemetry_f_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; i>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); -} -#endif - -/** - * @brief Initiliaze the buffer for the X.25 CRC - * - * @param crcAccum the 16 bit X.25 CRC - */ -static inline void crc_init(uint16_t* crcAccum) -{ - *crcAccum = X25_INIT_CRC; -} - - -/** - * @brief Calculates the X.25 checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) -{ - uint16_t crcTmp; - crc_init(&crcTmp); - while (length--) { - crc_accumulate(*pBuffer++, &crcTmp); - } - return crcTmp; -} - -/** - * @brief Accumulate the X.25 CRC by adding an array of bytes - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new bytes to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length) -{ - const uint8_t *p = (const uint8_t *)pBuffer; - while (length--) { - crc_accumulate(*p++, crcAccum); - } -} - - - - -#endif /* _CHECKSUM_H_ */ - -#ifdef __cplusplus -} -#endif diff --git a/mavlink/include/mavlink/v1.0/common/common.h b/mavlink/include/mavlink/v1.0/common/common.h deleted file mode 100644 index de6e22011..000000000 --- a/mavlink/include/mavlink/v1.0/common/common.h +++ /dev/null @@ -1,670 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from common.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef COMMON_H -#define COMMON_H - -#ifndef MAVLINK_H - #error Wrong include order: common.h MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set all defines from mavlink.h manually. -#endif - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} -#endif - -#ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_COMMON - -// ENUM DEFINITIONS - - -/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */ -#ifndef HAVE_ENUM_MAV_AUTOPILOT -#define HAVE_ENUM_MAV_AUTOPILOT -enum MAV_AUTOPILOT -{ - MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */ - MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */ - MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */ - MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */ - MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */ - MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */ - MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */ - MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */ - MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */ - MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */ - MAV_AUTOPILOT_FP=11, /* FlexiPilot | */ - MAV_AUTOPILOT_PX4=12, /* PX4 Autopilot - http://pixhawk.ethz.ch/px4/ | */ - MAV_AUTOPILOT_SMACCMPILOT=13, /* SMACCMPilot - http://smaccmpilot.org | */ - MAV_AUTOPILOT_AUTOQUAD=14, /* AutoQuad -- http://autoquad.org | */ - MAV_AUTOPILOT_ARMAZILA=15, /* Armazila -- http://armazila.com | */ - MAV_AUTOPILOT_AEROB=16, /* Aerob -- http://aerob.ru | */ - MAV_AUTOPILOT_ENUM_END=17, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_TYPE -#define HAVE_ENUM_MAV_TYPE -enum MAV_TYPE -{ - MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */ - MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */ - MAV_TYPE_QUADROTOR=2, /* Quadrotor | */ - MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */ - MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */ - MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */ - MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */ - MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */ - MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */ - MAV_TYPE_ROCKET=9, /* Rocket | */ - MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */ - MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */ - MAV_TYPE_SUBMARINE=12, /* Submarine | */ - MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */ - MAV_TYPE_OCTOROTOR=14, /* Octorotor | */ - MAV_TYPE_TRICOPTER=15, /* Octorotor | */ - MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */ - MAV_TYPE_KITE=17, /* Flapping wing | */ - MAV_TYPE_ONBOARD_CONTROLLER=18, /* Onboard companion controller | */ - MAV_TYPE_ENUM_END=19, /* | */ -}; -#endif - -/** @brief These flags encode the MAV mode. */ -#ifndef HAVE_ENUM_MAV_MODE_FLAG -#define HAVE_ENUM_MAV_MODE_FLAG -enum MAV_MODE_FLAG -{ - MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */ - MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */ - MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */ - MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */ - MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */ - MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */ - MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */ - MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */ - MAV_MODE_FLAG_ENUM_END=129, /* | */ -}; -#endif - -/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */ -#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION -#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION -enum MAV_MODE_FLAG_DECODE_POSITION -{ - MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */ - MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */ - MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */ - MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */ - MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */ - MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */ - MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */ - MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */ -}; -#endif - -/** @brief Override command, pauses current mission execution and moves immediately to a position */ -#ifndef HAVE_ENUM_MAV_GOTO -#define HAVE_ENUM_MAV_GOTO -enum MAV_GOTO -{ - MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */ - MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */ - MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */ - MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */ - MAV_GOTO_ENUM_END=4, /* | */ -}; -#endif - -/** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it - simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */ -#ifndef HAVE_ENUM_MAV_MODE -#define HAVE_ENUM_MAV_MODE -enum MAV_MODE -{ - MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */ - MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ - MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */ - MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */ - MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */ - MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */ - MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */ - MAV_MODE_ENUM_END=221, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_STATE -#define HAVE_ENUM_MAV_STATE -enum MAV_STATE -{ - MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */ - MAV_STATE_BOOT=1, /* System is booting up. | */ - MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */ - MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */ - MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */ - MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */ - MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */ - MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */ - MAV_STATE_ENUM_END=8, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_COMPONENT -#define HAVE_ENUM_MAV_COMPONENT -enum MAV_COMPONENT -{ - MAV_COMP_ID_ALL=0, /* | */ - MAV_COMP_ID_CAMERA=100, /* | */ - MAV_COMP_ID_SERVO1=140, /* | */ - MAV_COMP_ID_SERVO2=141, /* | */ - MAV_COMP_ID_SERVO3=142, /* | */ - MAV_COMP_ID_SERVO4=143, /* | */ - MAV_COMP_ID_SERVO5=144, /* | */ - MAV_COMP_ID_SERVO6=145, /* | */ - MAV_COMP_ID_SERVO7=146, /* | */ - MAV_COMP_ID_SERVO8=147, /* | */ - MAV_COMP_ID_SERVO9=148, /* | */ - MAV_COMP_ID_SERVO10=149, /* | */ - MAV_COMP_ID_SERVO11=150, /* | */ - MAV_COMP_ID_SERVO12=151, /* | */ - MAV_COMP_ID_SERVO13=152, /* | */ - MAV_COMP_ID_SERVO14=153, /* | */ - MAV_COMP_ID_MAPPER=180, /* | */ - MAV_COMP_ID_MISSIONPLANNER=190, /* | */ - MAV_COMP_ID_PATHPLANNER=195, /* | */ - MAV_COMP_ID_IMU=200, /* | */ - MAV_COMP_ID_IMU_2=201, /* | */ - MAV_COMP_ID_IMU_3=202, /* | */ - MAV_COMP_ID_GPS=220, /* | */ - MAV_COMP_ID_UDP_BRIDGE=240, /* | */ - MAV_COMP_ID_UART_BRIDGE=241, /* | */ - MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */ - MAV_COMPONENT_ENUM_END=251, /* | */ -}; -#endif - -/** @brief These encode the sensors whose status is sent as part of the SYS_STATUS message. */ -#ifndef HAVE_ENUM_MAV_SYS_STATUS_SENSOR -#define HAVE_ENUM_MAV_SYS_STATUS_SENSOR -enum MAV_SYS_STATUS_SENSOR -{ - MAV_SYS_STATUS_SENSOR_3D_GYRO=1, /* 0x01 3D gyro | */ - MAV_SYS_STATUS_SENSOR_3D_ACCEL=2, /* 0x02 3D accelerometer | */ - MAV_SYS_STATUS_SENSOR_3D_MAG=4, /* 0x04 3D magnetometer | */ - MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE=8, /* 0x08 absolute pressure | */ - MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE=16, /* 0x10 differential pressure | */ - MAV_SYS_STATUS_SENSOR_GPS=32, /* 0x20 GPS | */ - MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW=64, /* 0x40 optical flow | */ - MAV_SYS_STATUS_SENSOR_VISION_POSITION=128, /* 0x80 computer vision position | */ - MAV_SYS_STATUS_SENSOR_LASER_POSITION=256, /* 0x100 laser based position | */ - MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH=512, /* 0x200 external ground truth (Vicon or Leica) | */ - MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL=1024, /* 0x400 3D angular rate control | */ - MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION=2048, /* 0x800 attitude stabilization | */ - MAV_SYS_STATUS_SENSOR_YAW_POSITION=4096, /* 0x1000 yaw position | */ - MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL=8192, /* 0x2000 z/altitude control | */ - MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL=16384, /* 0x4000 x/y position control | */ - MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS=32768, /* 0x8000 motor outputs / control | */ - MAV_SYS_STATUS_SENSOR_RC_RECEIVER=65536, /* 0x10000 rc receiver | */ - MAV_SYS_STATUS_SENSOR_3D_GYRO2=131072, /* 0x20000 2nd 3D gyro | */ - MAV_SYS_STATUS_SENSOR_3D_ACCEL2=262144, /* 0x40000 2nd 3D accelerometer | */ - MAV_SYS_STATUS_SENSOR_3D_MAG2=524288, /* 0x80000 2nd 3D magnetometer | */ - MAV_SYS_STATUS_GEOFENCE=1048576, /* 0x100000 geofence | */ - MAV_SYS_STATUS_SENSOR_ENUM_END=1048577, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_FRAME -#define HAVE_ENUM_MAV_FRAME -enum MAV_FRAME -{ - MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */ - MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */ - MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */ - MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */ - MAV_FRAME_GLOBAL_INT=5, /* Global coordinate frame with some fields as scaled integers, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL). Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. | */ - MAV_FRAME_GLOBAL_RELATIVE_ALT_INT=6, /* Global coordinate frame with some fields as scaled integers, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. Lat / Lon are scaled * 1E7 to avoid floating point accuracy limitations. | */ - MAV_FRAME_ENUM_END=7, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE -#define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE -enum MAVLINK_DATA_STREAM_TYPE -{ - MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */ - MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW8U=3, /* | */ - MAVLINK_DATA_STREAM_IMG_RAW32U=4, /* | */ - MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */ - MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */ - MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_FENCE_ACTION -#define HAVE_ENUM_FENCE_ACTION -enum FENCE_ACTION -{ - FENCE_ACTION_NONE=0, /* Disable fenced mode | */ - FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */ - FENCE_ACTION_REPORT=2, /* Report fence breach, but don't take action | */ - FENCE_ACTION_GUIDED_THR_PASS=3, /* Switched to guided mode to return point (fence point 0) with manual throttle control | */ - FENCE_ACTION_ENUM_END=4, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_FENCE_BREACH -#define HAVE_ENUM_FENCE_BREACH -enum FENCE_BREACH -{ - FENCE_BREACH_NONE=0, /* No last fence breach | */ - FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */ - FENCE_BREACH_MAXALT=2, /* Breached maximum altitude | */ - FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */ - FENCE_BREACH_ENUM_END=4, /* | */ -}; -#endif - -/** @brief Enumeration of possible mount operation modes */ -#ifndef HAVE_ENUM_MAV_MOUNT_MODE -#define HAVE_ENUM_MAV_MOUNT_MODE -enum MAV_MOUNT_MODE -{ - MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from permant memory and stop stabilization | */ - MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory. | */ - MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */ - MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */ - MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */ - MAV_MOUNT_MODE_ENUM_END=5, /* | */ -}; -#endif - -/** @brief Enumeration of distance sensor types */ -#ifndef HAVE_ENUM_MAV_DISTANCE_SENSOR -#define HAVE_ENUM_MAV_DISTANCE_SENSOR -enum MAV_DISTANCE_SENSOR -{ - MAV_DISTANCE_SENSOR_LASER=0, /* Laser altimeter, e.g. LightWare SF02/F or PulsedLight units | */ - MAV_DISTANCE_SENSOR_ULTRASOUND=1, /* Laser altimeter, e.g. MaxBotix units | */ - MAV_DISTANCE_SENSOR_ENUM_END=2, /* | */ -}; -#endif - -/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. */ -#ifndef HAVE_ENUM_MAV_CMD -#define HAVE_ENUM_MAV_CMD -enum MAV_CMD -{ - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* 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. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - 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_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 sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ - MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ - MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ - MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */ - 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| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - 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| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ - MAV_CMD_ENUM_END=501, /* | */ -}; -#endif - -/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a - recommendation to the autopilot software. Individual autopilots may or may not obey - the recommended messages. */ -#ifndef HAVE_ENUM_MAV_DATA_STREAM -#define HAVE_ENUM_MAV_DATA_STREAM -enum MAV_DATA_STREAM -{ - MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */ - MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */ - MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */ - MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */ - MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */ - MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */ - MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */ - MAV_DATA_STREAM_ENUM_END=13, /* | */ -}; -#endif - -/** @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). */ -#ifndef HAVE_ENUM_MAV_ROI -#define HAVE_ENUM_MAV_ROI -enum MAV_ROI -{ - MAV_ROI_NONE=0, /* No region of interest. | */ - MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */ - MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */ - MAV_ROI_LOCATION=3, /* Point toward fixed location. | */ - MAV_ROI_TARGET=4, /* Point toward of given id. | */ - MAV_ROI_ENUM_END=5, /* | */ -}; -#endif - -/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */ -#ifndef HAVE_ENUM_MAV_CMD_ACK -#define HAVE_ENUM_MAV_CMD_ACK -enum MAV_CMD_ACK -{ - MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */ - MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */ - MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */ - MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */ - MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */ - MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */ - MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */ - MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */ - MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */ - MAV_CMD_ACK_ENUM_END=10, /* | */ -}; -#endif - -/** @brief Specifies the datatype of a MAVLink parameter. */ -#ifndef HAVE_ENUM_MAV_PARAM_TYPE -#define HAVE_ENUM_MAV_PARAM_TYPE -enum MAV_PARAM_TYPE -{ - MAV_PARAM_TYPE_UINT8=1, /* 8-bit unsigned integer | */ - MAV_PARAM_TYPE_INT8=2, /* 8-bit signed integer | */ - MAV_PARAM_TYPE_UINT16=3, /* 16-bit unsigned integer | */ - MAV_PARAM_TYPE_INT16=4, /* 16-bit signed integer | */ - MAV_PARAM_TYPE_UINT32=5, /* 32-bit unsigned integer | */ - MAV_PARAM_TYPE_INT32=6, /* 32-bit signed integer | */ - MAV_PARAM_TYPE_UINT64=7, /* 64-bit unsigned integer | */ - MAV_PARAM_TYPE_INT64=8, /* 64-bit signed integer | */ - MAV_PARAM_TYPE_REAL32=9, /* 32-bit floating-point | */ - MAV_PARAM_TYPE_REAL64=10, /* 64-bit floating-point | */ - MAV_PARAM_TYPE_ENUM_END=11, /* | */ -}; -#endif - -/** @brief result from a mavlink command */ -#ifndef HAVE_ENUM_MAV_RESULT -#define HAVE_ENUM_MAV_RESULT -enum MAV_RESULT -{ - MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */ - MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */ - MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */ - MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */ - MAV_RESULT_FAILED=4, /* Command executed, but failed | */ - MAV_RESULT_ENUM_END=5, /* | */ -}; -#endif - -/** @brief result in a mavlink mission ack */ -#ifndef HAVE_ENUM_MAV_MISSION_RESULT -#define HAVE_ENUM_MAV_MISSION_RESULT -enum MAV_MISSION_RESULT -{ - MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */ - MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */ - MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */ - MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */ - MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */ - MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */ - MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */ - MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */ - MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */ - MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */ - MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */ - MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */ - MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */ - MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */ - MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */ - MAV_MISSION_RESULT_ENUM_END=15, /* | */ -}; -#endif - -/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */ -#ifndef HAVE_ENUM_MAV_SEVERITY -#define HAVE_ENUM_MAV_SEVERITY -enum MAV_SEVERITY -{ - MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */ - MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */ - MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */ - MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */ - MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */ - MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */ - MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */ - MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */ - MAV_SEVERITY_ENUM_END=8, /* | */ -}; -#endif - -/** @brief Power supply status flags (bitmask) */ -#ifndef HAVE_ENUM_MAV_POWER_STATUS -#define HAVE_ENUM_MAV_POWER_STATUS -enum MAV_POWER_STATUS -{ - MAV_POWER_STATUS_BRICK_VALID=1, /* main brick power supply valid | */ - MAV_POWER_STATUS_SERVO_VALID=2, /* main servo power supply valid for FMU | */ - MAV_POWER_STATUS_USB_CONNECTED=4, /* USB power is connected | */ - MAV_POWER_STATUS_PERIPH_OVERCURRENT=8, /* peripheral supply is in over-current state | */ - MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT=16, /* hi-power peripheral supply is in over-current state | */ - MAV_POWER_STATUS_CHANGED=32, /* Power status has changed since boot | */ - MAV_POWER_STATUS_ENUM_END=33, /* | */ -}; -#endif - -/** @brief SERIAL_CONTROL device types */ -#ifndef HAVE_ENUM_SERIAL_CONTROL_DEV -#define HAVE_ENUM_SERIAL_CONTROL_DEV -enum SERIAL_CONTROL_DEV -{ - SERIAL_CONTROL_DEV_TELEM1=0, /* First telemetry port | */ - SERIAL_CONTROL_DEV_TELEM2=1, /* Second telemetry port | */ - SERIAL_CONTROL_DEV_GPS1=2, /* First GPS port | */ - SERIAL_CONTROL_DEV_GPS2=3, /* Second GPS port | */ - SERIAL_CONTROL_DEV_ENUM_END=4, /* | */ -}; -#endif - -/** @brief SERIAL_CONTROL flags (bitmask) */ -#ifndef HAVE_ENUM_SERIAL_CONTROL_FLAG -#define HAVE_ENUM_SERIAL_CONTROL_FLAG -enum SERIAL_CONTROL_FLAG -{ - SERIAL_CONTROL_FLAG_REPLY=1, /* Set if this is a reply | */ - SERIAL_CONTROL_FLAG_RESPOND=2, /* Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message | */ - SERIAL_CONTROL_FLAG_EXCLUSIVE=4, /* Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set | */ - SERIAL_CONTROL_FLAG_BLOCKING=8, /* Block on writes to the serial port | */ - SERIAL_CONTROL_FLAG_MULTI=16, /* Send multiple replies until port is drained | */ - SERIAL_CONTROL_FLAG_ENUM_END=17, /* | */ -}; -#endif - - - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_heartbeat.h" -#include "./mavlink_msg_sys_status.h" -#include "./mavlink_msg_system_time.h" -#include "./mavlink_msg_ping.h" -#include "./mavlink_msg_change_operator_control.h" -#include "./mavlink_msg_change_operator_control_ack.h" -#include "./mavlink_msg_auth_key.h" -#include "./mavlink_msg_set_mode.h" -#include "./mavlink_msg_param_request_read.h" -#include "./mavlink_msg_param_request_list.h" -#include "./mavlink_msg_param_value.h" -#include "./mavlink_msg_param_set.h" -#include "./mavlink_msg_gps_raw_int.h" -#include "./mavlink_msg_gps_status.h" -#include "./mavlink_msg_scaled_imu.h" -#include "./mavlink_msg_raw_imu.h" -#include "./mavlink_msg_raw_pressure.h" -#include "./mavlink_msg_scaled_pressure.h" -#include "./mavlink_msg_attitude.h" -#include "./mavlink_msg_attitude_quaternion.h" -#include "./mavlink_msg_local_position_ned.h" -#include "./mavlink_msg_global_position_int.h" -#include "./mavlink_msg_rc_channels_scaled.h" -#include "./mavlink_msg_rc_channels_raw.h" -#include "./mavlink_msg_servo_output_raw.h" -#include "./mavlink_msg_mission_request_partial_list.h" -#include "./mavlink_msg_mission_write_partial_list.h" -#include "./mavlink_msg_mission_item.h" -#include "./mavlink_msg_mission_request.h" -#include "./mavlink_msg_mission_set_current.h" -#include "./mavlink_msg_mission_current.h" -#include "./mavlink_msg_mission_request_list.h" -#include "./mavlink_msg_mission_count.h" -#include "./mavlink_msg_mission_clear_all.h" -#include "./mavlink_msg_mission_item_reached.h" -#include "./mavlink_msg_mission_ack.h" -#include "./mavlink_msg_set_gps_global_origin.h" -#include "./mavlink_msg_gps_global_origin.h" -#include "./mavlink_msg_set_local_position_setpoint.h" -#include "./mavlink_msg_local_position_setpoint.h" -#include "./mavlink_msg_global_position_setpoint_int.h" -#include "./mavlink_msg_set_global_position_setpoint_int.h" -#include "./mavlink_msg_safety_set_allowed_area.h" -#include "./mavlink_msg_safety_allowed_area.h" -#include "./mavlink_msg_set_roll_pitch_yaw_thrust.h" -#include "./mavlink_msg_set_roll_pitch_yaw_speed_thrust.h" -#include "./mavlink_msg_roll_pitch_yaw_thrust_setpoint.h" -#include "./mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h" -#include "./mavlink_msg_set_quad_motors_setpoint.h" -#include "./mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h" -#include "./mavlink_msg_nav_controller_output.h" -#include "./mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h" -#include "./mavlink_msg_state_correction.h" -#include "./mavlink_msg_rc_channels.h" -#include "./mavlink_msg_request_data_stream.h" -#include "./mavlink_msg_data_stream.h" -#include "./mavlink_msg_manual_control.h" -#include "./mavlink_msg_rc_channels_override.h" -#include "./mavlink_msg_vfr_hud.h" -#include "./mavlink_msg_command_long.h" -#include "./mavlink_msg_command_ack.h" -#include "./mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h" -#include "./mavlink_msg_manual_setpoint.h" -#include "./mavlink_msg_local_position_ned_system_global_offset.h" -#include "./mavlink_msg_hil_state.h" -#include "./mavlink_msg_hil_controls.h" -#include "./mavlink_msg_hil_rc_inputs_raw.h" -#include "./mavlink_msg_optical_flow.h" -#include "./mavlink_msg_global_vision_position_estimate.h" -#include "./mavlink_msg_vision_position_estimate.h" -#include "./mavlink_msg_vision_speed_estimate.h" -#include "./mavlink_msg_vicon_position_estimate.h" -#include "./mavlink_msg_highres_imu.h" -#include "./mavlink_msg_omnidirectional_flow.h" -#include "./mavlink_msg_hil_sensor.h" -#include "./mavlink_msg_sim_state.h" -#include "./mavlink_msg_radio_status.h" -#include "./mavlink_msg_file_transfer_start.h" -#include "./mavlink_msg_file_transfer_dir_list.h" -#include "./mavlink_msg_file_transfer_res.h" -#include "./mavlink_msg_hil_gps.h" -#include "./mavlink_msg_hil_optical_flow.h" -#include "./mavlink_msg_hil_state_quaternion.h" -#include "./mavlink_msg_scaled_imu2.h" -#include "./mavlink_msg_log_request_list.h" -#include "./mavlink_msg_log_entry.h" -#include "./mavlink_msg_log_request_data.h" -#include "./mavlink_msg_log_data.h" -#include "./mavlink_msg_log_erase.h" -#include "./mavlink_msg_log_request_end.h" -#include "./mavlink_msg_gps_inject_data.h" -#include "./mavlink_msg_gps2_raw.h" -#include "./mavlink_msg_power_status.h" -#include "./mavlink_msg_serial_control.h" -#include "./mavlink_msg_data_transmission_handshake.h" -#include "./mavlink_msg_encapsulated_data.h" -#include "./mavlink_msg_distance_sensor.h" -#include "./mavlink_msg_battery_status.h" -#include "./mavlink_msg_setpoint_8dof.h" -#include "./mavlink_msg_setpoint_6dof.h" -#include "./mavlink_msg_memory_vect.h" -#include "./mavlink_msg_debug_vect.h" -#include "./mavlink_msg_named_value_float.h" -#include "./mavlink_msg_named_value_int.h" -#include "./mavlink_msg_statustext.h" -#include "./mavlink_msg_debug.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // COMMON_H diff --git a/mavlink/include/mavlink/v1.0/common/mavlink.h b/mavlink/include/mavlink/v1.0/common/mavlink.h deleted file mode 100644 index 17b732970..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink.h +++ /dev/null @@ -1,27 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from common.xml - * @see http://pixhawk.ethz.ch/software/mavlink - */ -#ifndef MAVLINK_H -#define MAVLINK_H - -#ifndef MAVLINK_STX -#define MAVLINK_STX 254 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#include "version.h" -#include "common.h" - -#endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h deleted file mode 100644 index ff2f104d4..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE ATTITUDE PACKING - -#define MAVLINK_MSG_ID_ATTITUDE 30 - -typedef struct __mavlink_attitude_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - float roll; ///< Roll angle (rad, -pi..+pi) - float pitch; ///< Pitch angle (rad, -pi..+pi) - float yaw; ///< Yaw angle (rad, -pi..+pi) - float rollspeed; ///< Roll angular speed (rad/s) - float pitchspeed; ///< Pitch angular speed (rad/s) - float yawspeed; ///< Yaw angular speed (rad/s) -} mavlink_attitude_t; - -#define MAVLINK_MSG_ID_ATTITUDE_LEN 28 -#define MAVLINK_MSG_ID_30_LEN 28 - -#define MAVLINK_MSG_ID_ATTITUDE_CRC 39 -#define MAVLINK_MSG_ID_30_CRC 39 - - - -#define MAVLINK_MESSAGE_INFO_ATTITUDE { \ - "ATTITUDE", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \ - } \ -} - - -/** - * @brief Pack a attitude message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif -} - -/** - * @brief Pack a attitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif -} - -/** - * @brief Encode a attitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude) -{ - return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -} - -/** - * @brief Encode a attitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude) -{ - return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed); -} - -/** - * @brief Send a attitude message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param roll Roll angle (rad, -pi..+pi) - * @param pitch Pitch angle (rad, -pi..+pi) - * @param yaw Yaw angle (rad, -pi..+pi) - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif -#else - mavlink_attitude_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, rollspeed); - _mav_put_float(buf, 20, pitchspeed); - _mav_put_float(buf, 24, yawspeed); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif -#else - mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from attitude message - * - * @return Roll angle (rad, -pi..+pi) - */ -static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from attitude message - * - * @return Pitch angle (rad, -pi..+pi) - */ -static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from attitude message - * - * @return Yaw angle (rad, -pi..+pi) - */ -static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field rollspeed from attitude message - * - * @return Roll angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitchspeed from attitude message - * - * @return Pitch angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yawspeed from attitude message - * - * @return Yaw angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a attitude message into a struct - * - * @param msg The message to decode - * @param attitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP - attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg); - attitude->roll = mavlink_msg_attitude_get_roll(msg); - attitude->pitch = mavlink_msg_attitude_get_pitch(msg); - attitude->yaw = mavlink_msg_attitude_get_yaw(msg); - attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg); - attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg); - attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg); -#else - memcpy(attitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h deleted file mode 100644 index 3b97b40d0..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h +++ /dev/null @@ -1,377 +0,0 @@ -// MESSAGE ATTITUDE_QUATERNION PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31 - -typedef struct __mavlink_attitude_quaternion_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - float q1; ///< Quaternion component 1 - float q2; ///< Quaternion component 2 - float q3; ///< Quaternion component 3 - float q4; ///< Quaternion component 4 - float rollspeed; ///< Roll angular speed (rad/s) - float pitchspeed; ///< Pitch angular speed (rad/s) - float yawspeed; ///< Yaw angular speed (rad/s) -} mavlink_attitude_quaternion_t; - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32 -#define MAVLINK_MSG_ID_31_LEN 32 - -#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246 -#define MAVLINK_MSG_ID_31_CRC 246 - - - -#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \ - "ATTITUDE_QUATERNION", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \ - { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \ - } \ -} - - -/** - * @brief Pack a attitude_quaternion message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1 - * @param q2 Quaternion component 2 - * @param q3 Quaternion component 3 - * @param q4 Quaternion component 4 - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#else - mavlink_attitude_quaternion_t packet; - packet.time_boot_ms = time_boot_ms; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif -} - -/** - * @brief Pack a attitude_quaternion message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1 - * @param q2 Quaternion component 2 - * @param q3 Quaternion component 3 - * @param q4 Quaternion component 4 - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#else - mavlink_attitude_quaternion_t packet; - packet.time_boot_ms = time_boot_ms; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif -} - -/** - * @brief Encode a attitude_quaternion struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ - return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); -} - -/** - * @brief Encode a attitude_quaternion struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion) -{ - return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed); -} - -/** - * @brief Send a attitude_quaternion message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param q1 Quaternion component 1 - * @param q2 Quaternion component 2 - * @param q3 Quaternion component 3 - * @param q4 Quaternion component 4 - * @param rollspeed Roll angular speed (rad/s) - * @param pitchspeed Pitch angular speed (rad/s) - * @param yawspeed Yaw angular speed (rad/s) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif -#else - mavlink_attitude_quaternion_t packet; - packet.time_boot_ms = time_boot_ms; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, q1); - _mav_put_float(buf, 8, q2); - _mav_put_float(buf, 12, q3); - _mav_put_float(buf, 16, q4); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif -#else - mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->q1 = q1; - packet->q2 = q2; - packet->q3 = q3; - packet->q4 = q4; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_QUATERNION UNPACKING - - -/** - * @brief Get field time_boot_ms from attitude_quaternion message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field q1 from attitude_quaternion message - * - * @return Quaternion component 1 - */ -static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field q2 from attitude_quaternion message - * - * @return Quaternion component 2 - */ -static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field q3 from attitude_quaternion message - * - * @return Quaternion component 3 - */ -static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field q4 from attitude_quaternion message - * - * @return Quaternion component 4 - */ -static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rollspeed from attitude_quaternion message - * - * @return Roll angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitchspeed from attitude_quaternion message - * - * @return Pitch angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yawspeed from attitude_quaternion message - * - * @return Yaw angular speed (rad/s) - */ -static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a attitude_quaternion message into a struct - * - * @param msg The message to decode - * @param attitude_quaternion C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP - attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg); - attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg); - attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg); - attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg); - attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg); - attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg); - attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg); - attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg); -#else - memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h deleted file mode 100644 index f31b6bbf4..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h +++ /dev/null @@ -1,209 +0,0 @@ -// MESSAGE AUTH_KEY PACKING - -#define MAVLINK_MSG_ID_AUTH_KEY 7 - -typedef struct __mavlink_auth_key_t -{ - char key[32]; ///< key -} mavlink_auth_key_t; - -#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32 -#define MAVLINK_MSG_ID_7_LEN 32 - -#define MAVLINK_MSG_ID_AUTH_KEY_CRC 119 -#define MAVLINK_MSG_ID_7_CRC 119 - -#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32 - -#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \ - "AUTH_KEY", \ - 1, \ - { { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \ - } \ -} - - -/** - * @brief Pack a auth_key message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param key key - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#else - mavlink_auth_key_t packet; - - mav_array_memcpy(packet.key, key, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif -} - -/** - * @brief Pack a auth_key message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param key key - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#else - mavlink_auth_key_t packet; - - mav_array_memcpy(packet.key, key, sizeof(char)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AUTH_KEY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif -} - -/** - * @brief Encode a auth_key struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param auth_key C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) -{ - return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key); -} - -/** - * @brief Encode a auth_key struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param auth_key C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_auth_key_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key) -{ - return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, msg, auth_key->key); -} - -/** - * @brief Send a auth_key message - * @param chan MAVLink channel to send the message - * - * @param key key - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AUTH_KEY_LEN]; - - _mav_put_char_array(buf, 0, key, 32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif -#else - mavlink_auth_key_t packet; - - mav_array_memcpy(packet.key, key, sizeof(char)*32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_char_array(buf, 0, key, 32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif -#else - mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf; - - mav_array_memcpy(packet->key, key, sizeof(char)*32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE AUTH_KEY UNPACKING - - -/** - * @brief Get field key from auth_key message - * - * @return key - */ -static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key) -{ - return _MAV_RETURN_char_array(msg, key, 32, 0); -} - -/** - * @brief Decode a auth_key message into a struct - * - * @param msg The message to decode - * @param auth_key C-struct to decode the message contents into - */ -static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_auth_key_get_key(msg, auth_key->key); -#else - memcpy(auth_key, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTH_KEY_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h deleted file mode 100644 index faaabf9f7..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_battery_status.h +++ /dev/null @@ -1,449 +0,0 @@ -// MESSAGE BATTERY_STATUS PACKING - -#define MAVLINK_MSG_ID_BATTERY_STATUS 147 - -typedef struct __mavlink_battery_status_t -{ - int32_t current_consumed; ///< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - int32_t energy_consumed; ///< Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - uint16_t voltage_cell_1; ///< Battery voltage of cell 1, in millivolts (1 = 1 millivolt) - uint16_t voltage_cell_2; ///< Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell - uint16_t voltage_cell_3; ///< Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell - uint16_t voltage_cell_4; ///< Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell - uint16_t voltage_cell_5; ///< Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell - uint16_t voltage_cell_6; ///< Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell - int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - uint8_t accu_id; ///< Accupack ID - int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery -} mavlink_battery_status_t; - -#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 24 -#define MAVLINK_MSG_ID_147_LEN 24 - -#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 177 -#define MAVLINK_MSG_ID_147_CRC 177 - - - -#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \ - "BATTERY_STATUS", \ - 11, \ - { { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \ - { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \ - { "voltage_cell_1", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_battery_status_t, voltage_cell_1) }, \ - { "voltage_cell_2", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_battery_status_t, voltage_cell_2) }, \ - { "voltage_cell_3", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_battery_status_t, voltage_cell_3) }, \ - { "voltage_cell_4", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_battery_status_t, voltage_cell_4) }, \ - { "voltage_cell_5", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_battery_status_t, voltage_cell_5) }, \ - { "voltage_cell_6", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_battery_status_t, voltage_cell_6) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_battery_status_t, current_battery) }, \ - { "accu_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_battery_status_t, accu_id) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 23, offsetof(mavlink_battery_status_t, battery_remaining) }, \ - } \ -} - - -/** - * @brief Pack a battery_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param accu_id Accupack ID - * @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt) - * @param voltage_cell_2 Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_3 Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_4 Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_uint16_t(buf, 8, voltage_cell_1); - _mav_put_uint16_t(buf, 10, voltage_cell_2); - _mav_put_uint16_t(buf, 12, voltage_cell_3); - _mav_put_uint16_t(buf, 14, voltage_cell_4); - _mav_put_uint16_t(buf, 16, voltage_cell_5); - _mav_put_uint16_t(buf, 18, voltage_cell_6); - _mav_put_int16_t(buf, 20, current_battery); - _mav_put_uint8_t(buf, 22, accu_id); - _mav_put_int8_t(buf, 23, battery_remaining); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.voltage_cell_1 = voltage_cell_1; - packet.voltage_cell_2 = voltage_cell_2; - packet.voltage_cell_3 = voltage_cell_3; - packet.voltage_cell_4 = voltage_cell_4; - packet.voltage_cell_5 = voltage_cell_5; - packet.voltage_cell_6 = voltage_cell_6; - packet.current_battery = current_battery; - packet.accu_id = accu_id; - packet.battery_remaining = battery_remaining; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif -} - -/** - * @brief Pack a battery_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param accu_id Accupack ID - * @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt) - * @param voltage_cell_2 Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_3 Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_4 Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t accu_id,uint16_t voltage_cell_1,uint16_t voltage_cell_2,uint16_t voltage_cell_3,uint16_t voltage_cell_4,uint16_t voltage_cell_5,uint16_t voltage_cell_6,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_uint16_t(buf, 8, voltage_cell_1); - _mav_put_uint16_t(buf, 10, voltage_cell_2); - _mav_put_uint16_t(buf, 12, voltage_cell_3); - _mav_put_uint16_t(buf, 14, voltage_cell_4); - _mav_put_uint16_t(buf, 16, voltage_cell_5); - _mav_put_uint16_t(buf, 18, voltage_cell_6); - _mav_put_int16_t(buf, 20, current_battery); - _mav_put_uint8_t(buf, 22, accu_id); - _mav_put_int8_t(buf, 23, battery_remaining); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.voltage_cell_1 = voltage_cell_1; - packet.voltage_cell_2 = voltage_cell_2; - packet.voltage_cell_3 = voltage_cell_3; - packet.voltage_cell_4 = voltage_cell_4; - packet.voltage_cell_5 = voltage_cell_5; - packet.voltage_cell_6 = voltage_cell_6; - packet.current_battery = current_battery; - packet.accu_id = accu_id; - packet.battery_remaining = battery_remaining; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif -} - -/** - * @brief Encode a battery_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param battery_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) -{ - return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->accu_id, battery_status->voltage_cell_1, battery_status->voltage_cell_2, battery_status->voltage_cell_3, battery_status->voltage_cell_4, battery_status->voltage_cell_5, battery_status->voltage_cell_6, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); -} - -/** - * @brief Encode a battery_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param battery_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status) -{ - return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->accu_id, battery_status->voltage_cell_1, battery_status->voltage_cell_2, battery_status->voltage_cell_3, battery_status->voltage_cell_4, battery_status->voltage_cell_5, battery_status->voltage_cell_6, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining); -} - -/** - * @brief Send a battery_status message - * @param chan MAVLink channel to send the message - * - * @param accu_id Accupack ID - * @param voltage_cell_1 Battery voltage of cell 1, in millivolts (1 = 1 millivolt) - * @param voltage_cell_2 Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_3 Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_4 Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_5 Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell - * @param voltage_cell_6 Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - * @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN]; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_uint16_t(buf, 8, voltage_cell_1); - _mav_put_uint16_t(buf, 10, voltage_cell_2); - _mav_put_uint16_t(buf, 12, voltage_cell_3); - _mav_put_uint16_t(buf, 14, voltage_cell_4); - _mav_put_uint16_t(buf, 16, voltage_cell_5); - _mav_put_uint16_t(buf, 18, voltage_cell_6); - _mav_put_int16_t(buf, 20, current_battery); - _mav_put_uint8_t(buf, 22, accu_id); - _mav_put_int8_t(buf, 23, battery_remaining); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif -#else - mavlink_battery_status_t packet; - packet.current_consumed = current_consumed; - packet.energy_consumed = energy_consumed; - packet.voltage_cell_1 = voltage_cell_1; - packet.voltage_cell_2 = voltage_cell_2; - packet.voltage_cell_3 = voltage_cell_3; - packet.voltage_cell_4 = voltage_cell_4; - packet.voltage_cell_5 = voltage_cell_5; - packet.voltage_cell_6 = voltage_cell_6; - packet.current_battery = current_battery; - packet.accu_id = accu_id; - packet.battery_remaining = battery_remaining; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t accu_id, uint16_t voltage_cell_1, uint16_t voltage_cell_2, uint16_t voltage_cell_3, uint16_t voltage_cell_4, uint16_t voltage_cell_5, uint16_t voltage_cell_6, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, current_consumed); - _mav_put_int32_t(buf, 4, energy_consumed); - _mav_put_uint16_t(buf, 8, voltage_cell_1); - _mav_put_uint16_t(buf, 10, voltage_cell_2); - _mav_put_uint16_t(buf, 12, voltage_cell_3); - _mav_put_uint16_t(buf, 14, voltage_cell_4); - _mav_put_uint16_t(buf, 16, voltage_cell_5); - _mav_put_uint16_t(buf, 18, voltage_cell_6); - _mav_put_int16_t(buf, 20, current_battery); - _mav_put_uint8_t(buf, 22, accu_id); - _mav_put_int8_t(buf, 23, battery_remaining); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif -#else - mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf; - packet->current_consumed = current_consumed; - packet->energy_consumed = energy_consumed; - packet->voltage_cell_1 = voltage_cell_1; - packet->voltage_cell_2 = voltage_cell_2; - packet->voltage_cell_3 = voltage_cell_3; - packet->voltage_cell_4 = voltage_cell_4; - packet->voltage_cell_5 = voltage_cell_5; - packet->voltage_cell_6 = voltage_cell_6; - packet->current_battery = current_battery; - packet->accu_id = accu_id; - packet->battery_remaining = battery_remaining; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE BATTERY_STATUS UNPACKING - - -/** - * @brief Get field accu_id from battery_status message - * - * @return Accupack ID - */ -static inline uint8_t mavlink_msg_battery_status_get_accu_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Get field voltage_cell_1 from battery_status message - * - * @return Battery voltage of cell 1, in millivolts (1 = 1 millivolt) - */ -static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field voltage_cell_2 from battery_status message - * - * @return Battery voltage of cell 2, in millivolts (1 = 1 millivolt), -1: no cell - */ -static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field voltage_cell_3 from battery_status message - * - * @return Battery voltage of cell 3, in millivolts (1 = 1 millivolt), -1: no cell - */ -static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field voltage_cell_4 from battery_status message - * - * @return Battery voltage of cell 4, in millivolts (1 = 1 millivolt), -1: no cell - */ -static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field voltage_cell_5 from battery_status message - * - * @return Battery voltage of cell 5, in millivolts (1 = 1 millivolt), -1: no cell - */ -static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field voltage_cell_6 from battery_status message - * - * @return Battery voltage of cell 6, in millivolts (1 = 1 millivolt), -1: no cell - */ -static inline uint16_t mavlink_msg_battery_status_get_voltage_cell_6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field current_battery from battery_status message - * - * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - */ -static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field current_consumed from battery_status message - * - * @return Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate - */ -static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field energy_consumed from battery_status message - * - * @return Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate - */ -static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field battery_remaining from battery_status message - * - * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery - */ -static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 23); -} - -/** - * @brief Decode a battery_status message into a struct - * - * @param msg The message to decode - * @param battery_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg); - battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg); - battery_status->voltage_cell_1 = mavlink_msg_battery_status_get_voltage_cell_1(msg); - battery_status->voltage_cell_2 = mavlink_msg_battery_status_get_voltage_cell_2(msg); - battery_status->voltage_cell_3 = mavlink_msg_battery_status_get_voltage_cell_3(msg); - battery_status->voltage_cell_4 = mavlink_msg_battery_status_get_voltage_cell_4(msg); - battery_status->voltage_cell_5 = mavlink_msg_battery_status_get_voltage_cell_5(msg); - battery_status->voltage_cell_6 = mavlink_msg_battery_status_get_voltage_cell_6(msg); - battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg); - battery_status->accu_id = mavlink_msg_battery_status_get_accu_id(msg); - battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg); -#else - memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h deleted file mode 100644 index 3f0987f10..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h +++ /dev/null @@ -1,273 +0,0 @@ -// MESSAGE CHANGE_OPERATOR_CONTROL PACKING - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5 - -typedef struct __mavlink_change_operator_control_t -{ - uint8_t target_system; ///< System the GCS requests control for - uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV - uint8_t version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - char passkey[25]; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" -} mavlink_change_operator_control_t; - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28 -#define MAVLINK_MSG_ID_5_LEN 28 - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC 217 -#define MAVLINK_MSG_ID_5_CRC 217 - -#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25 - -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \ - "CHANGE_OPERATOR_CONTROL", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \ - { "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \ - { "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \ - } \ -} - - -/** - * @brief Pack a change_operator_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, version); - _mav_put_char_array(buf, 3, passkey, 25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#else - mavlink_change_operator_control_t packet; - packet.target_system = target_system; - packet.control_request = control_request; - packet.version = version; - mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif -} - -/** - * @brief Pack a change_operator_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, version); - _mav_put_char_array(buf, 3, passkey, 25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#else - mavlink_change_operator_control_t packet; - packet.target_system = target_system; - packet.control_request = control_request; - packet.version = version; - mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif -} - -/** - * @brief Encode a change_operator_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param change_operator_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) -{ - return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -} - -/** - * @brief Encode a change_operator_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param change_operator_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control) -{ - return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey); -} - -/** - * @brief Send a change_operator_control message - * @param chan MAVLink channel to send the message - * - * @param target_system System the GCS requests control for - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - * @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, version); - _mav_put_char_array(buf, 3, passkey, 25); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif -#else - mavlink_change_operator_control_t packet; - packet.target_system = target_system; - packet.control_request = control_request; - packet.version = version; - mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, version); - _mav_put_char_array(buf, 3, passkey, 25); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif -#else - mavlink_change_operator_control_t *packet = (mavlink_change_operator_control_t *)msgbuf; - packet->target_system = target_system; - packet->control_request = control_request; - packet->version = version; - mav_array_memcpy(packet->passkey, passkey, sizeof(char)*25); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING - - -/** - * @brief Get field target_system from change_operator_control message - * - * @return System the GCS requests control for - */ -static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field control_request from change_operator_control message - * - * @return 0: request control of this MAV, 1: Release control of this MAV - */ -static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field version from change_operator_control message - * - * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. - */ -static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field passkey from change_operator_control message - * - * @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" - */ -static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey) -{ - return _MAV_RETURN_char_array(msg, passkey, 25, 3); -} - -/** - * @brief Decode a change_operator_control message into a struct - * - * @param msg The message to decode - * @param change_operator_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control) -{ -#if MAVLINK_NEED_BYTE_SWAP - change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg); - change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg); - change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg); - mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey); -#else - memcpy(change_operator_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h deleted file mode 100644 index 768e7ed5c..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6 - -typedef struct __mavlink_change_operator_control_ack_t -{ - uint8_t gcs_system_id; ///< ID of the GCS this message - uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV - uint8_t ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control -} mavlink_change_operator_control_ack_t; - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3 -#define MAVLINK_MSG_ID_6_LEN 3 - -#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104 -#define MAVLINK_MSG_ID_6_CRC 104 - - - -#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \ - "CHANGE_OPERATOR_CONTROL_ACK", \ - 3, \ - { { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \ - { "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \ - { "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \ - } \ -} - - -/** - * @brief Pack a change_operator_control_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; - _mav_put_uint8_t(buf, 0, gcs_system_id); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, ack); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#else - mavlink_change_operator_control_ack_t packet; - packet.gcs_system_id = gcs_system_id; - packet.control_request = control_request; - packet.ack = ack; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif -} - -/** - * @brief Pack a change_operator_control_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t gcs_system_id,uint8_t control_request,uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; - _mav_put_uint8_t(buf, 0, gcs_system_id); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, ack); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#else - mavlink_change_operator_control_ack_t packet; - packet.gcs_system_id = gcs_system_id; - packet.control_request = control_request; - packet.ack = ack; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif -} - -/** - * @brief Encode a change_operator_control_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param change_operator_control_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ - return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -} - -/** - * @brief Encode a change_operator_control_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param change_operator_control_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_change_operator_control_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ - return mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, chan, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack); -} - -/** - * @brief Send a change_operator_control_ack message - * @param chan MAVLink channel to send the message - * - * @param gcs_system_id ID of the GCS this message - * @param control_request 0: request control of this MAV, 1: Release control of this MAV - * @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN]; - _mav_put_uint8_t(buf, 0, gcs_system_id); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, ack); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif -#else - mavlink_change_operator_control_ack_t packet; - packet.gcs_system_id = gcs_system_id; - packet.control_request = control_request; - packet.ack = ack; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_change_operator_control_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, gcs_system_id); - _mav_put_uint8_t(buf, 1, control_request); - _mav_put_uint8_t(buf, 2, ack); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif -#else - mavlink_change_operator_control_ack_t *packet = (mavlink_change_operator_control_ack_t *)msgbuf; - packet->gcs_system_id = gcs_system_id; - packet->control_request = control_request; - packet->ack = ack; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING - - -/** - * @brief Get field gcs_system_id from change_operator_control_ack message - * - * @return ID of the GCS this message - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field control_request from change_operator_control_ack message - * - * @return 0: request control of this MAV, 1: Release control of this MAV - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field ack from change_operator_control_ack message - * - * @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control - */ -static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a change_operator_control_ack message into a struct - * - * @param msg The message to decode - * @param change_operator_control_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP - change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg); - change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg); - change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg); -#else - memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h deleted file mode 100644 index d3d163041..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE COMMAND_ACK PACKING - -#define MAVLINK_MSG_ID_COMMAND_ACK 77 - -typedef struct __mavlink_command_ack_t -{ - uint16_t command; ///< Command ID, as defined by MAV_CMD enum. - uint8_t result; ///< See MAV_RESULT enum -} mavlink_command_ack_t; - -#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3 -#define MAVLINK_MSG_ID_77_LEN 3 - -#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143 -#define MAVLINK_MSG_ID_77_CRC 143 - - - -#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \ - "COMMAND_ACK", \ - 2, \ - { { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \ - { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \ - } \ -} - - -/** - * @brief Pack a command_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t command, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#else - mavlink_command_ack_t packet; - packet.command = command; - packet.result = result; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif -} - -/** - * @brief Pack a command_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t command,uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#else - mavlink_command_ack_t packet; - packet.command = command; - packet.result = result; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif -} - -/** - * @brief Encode a command_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) -{ - return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result); -} - -/** - * @brief Encode a command_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack) -{ - return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result); -} - -/** - * @brief Send a command_ack message - * @param chan MAVLink channel to send the message - * - * @param command Command ID, as defined by MAV_CMD enum. - * @param result See MAV_RESULT enum - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_ACK_LEN]; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif -#else - mavlink_command_ack_t packet; - packet.command = command; - packet.result = result; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, command); - _mav_put_uint8_t(buf, 2, result); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif -#else - mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf; - packet->command = command; - packet->result = result; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_ACK UNPACKING - - -/** - * @brief Get field command from command_ack message - * - * @return Command ID, as defined by MAV_CMD enum. - */ -static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field result from command_ack message - * - * @return See MAV_RESULT enum - */ -static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a command_ack message into a struct - * - * @param msg The message to decode - * @param command_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP - command_ack->command = mavlink_msg_command_ack_get_command(msg); - command_ack->result = mavlink_msg_command_ack_get_result(msg); -#else - memcpy(command_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_ACK_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h deleted file mode 100644 index 161896b97..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_command_long.h +++ /dev/null @@ -1,449 +0,0 @@ -// MESSAGE COMMAND_LONG PACKING - -#define MAVLINK_MSG_ID_COMMAND_LONG 76 - -typedef struct __mavlink_command_long_t -{ - float param1; ///< Parameter 1, as defined by MAV_CMD enum. - float param2; ///< Parameter 2, as defined by MAV_CMD enum. - float param3; ///< Parameter 3, as defined by MAV_CMD enum. - float param4; ///< Parameter 4, as defined by MAV_CMD enum. - float param5; ///< Parameter 5, as defined by MAV_CMD enum. - float param6; ///< Parameter 6, as defined by MAV_CMD enum. - float param7; ///< Parameter 7, as defined by MAV_CMD enum. - uint16_t command; ///< Command ID, as defined by MAV_CMD enum. - uint8_t target_system; ///< System which should execute the command - uint8_t target_component; ///< Component which should execute the command, 0 for all components - uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) -} mavlink_command_long_t; - -#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33 -#define MAVLINK_MSG_ID_76_LEN 33 - -#define MAVLINK_MSG_ID_COMMAND_LONG_CRC 152 -#define MAVLINK_MSG_ID_76_CRC 152 - - - -#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \ - "COMMAND_LONG", \ - 11, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \ - { "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \ - { "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \ - { "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \ - { "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \ - } \ -} - - -/** - * @brief Pack a command_long message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif -} - -/** - * @brief Pack a command_long message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_command_long_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif -} - -/** - * @brief Encode a command_long struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param command_long C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long) -{ - return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -} - -/** - * @brief Encode a command_long struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_long C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_command_long_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long) -{ - return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7); -} - -/** - * @brief Send a command_long message - * @param chan MAVLink channel to send the message - * - * @param target_system System which should execute the command - * @param target_component Component which should execute the command, 0 for all components - * @param command Command ID, as defined by MAV_CMD enum. - * @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - * @param param1 Parameter 1, as defined by MAV_CMD enum. - * @param param2 Parameter 2, as defined by MAV_CMD enum. - * @param param3 Parameter 3, as defined by MAV_CMD enum. - * @param param4 Parameter 4, as defined by MAV_CMD enum. - * @param param5 Parameter 5, as defined by MAV_CMD enum. - * @param param6 Parameter 6, as defined by MAV_CMD enum. - * @param param7 Parameter 7, as defined by MAV_CMD enum. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_COMMAND_LONG_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif -#else - mavlink_command_long_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.param5 = param5; - packet.param6 = param6; - packet.param7 = param7; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.confirmation = confirmation; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, param5); - _mav_put_float(buf, 20, param6); - _mav_put_float(buf, 24, param7); - _mav_put_uint16_t(buf, 28, command); - _mav_put_uint8_t(buf, 30, target_system); - _mav_put_uint8_t(buf, 31, target_component); - _mav_put_uint8_t(buf, 32, confirmation); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif -#else - mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->param5 = param5; - packet->param6 = param6; - packet->param7 = param7; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->confirmation = confirmation; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE COMMAND_LONG UNPACKING - - -/** - * @brief Get field target_system from command_long message - * - * @return System which should execute the command - */ -static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 30); -} - -/** - * @brief Get field target_component from command_long message - * - * @return Component which should execute the command, 0 for all components - */ -static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 31); -} - -/** - * @brief Get field command from command_long message - * - * @return Command ID, as defined by MAV_CMD enum. - */ -static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field confirmation from command_long message - * - * @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) - */ -static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field param1 from command_long message - * - * @return Parameter 1, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from command_long message - * - * @return Parameter 2, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from command_long message - * - * @return Parameter 3, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from command_long message - * - * @return Parameter 4, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field param5 from command_long message - * - * @return Parameter 5, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field param6 from command_long message - * - * @return Parameter 6, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field param7 from command_long message - * - * @return Parameter 7, as defined by MAV_CMD enum. - */ -static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a command_long message into a struct - * - * @param msg The message to decode - * @param command_long C-struct to decode the message contents into - */ -static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long) -{ -#if MAVLINK_NEED_BYTE_SWAP - command_long->param1 = mavlink_msg_command_long_get_param1(msg); - command_long->param2 = mavlink_msg_command_long_get_param2(msg); - command_long->param3 = mavlink_msg_command_long_get_param3(msg); - command_long->param4 = mavlink_msg_command_long_get_param4(msg); - command_long->param5 = mavlink_msg_command_long_get_param5(msg); - command_long->param6 = mavlink_msg_command_long_get_param6(msg); - command_long->param7 = mavlink_msg_command_long_get_param7(msg); - command_long->command = mavlink_msg_command_long_get_command(msg); - command_long->target_system = mavlink_msg_command_long_get_target_system(msg); - command_long->target_component = mavlink_msg_command_long_get_target_component(msg); - command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg); -#else - memcpy(command_long, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_LONG_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h deleted file mode 100644 index 640ffebf4..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE DATA_STREAM PACKING - -#define MAVLINK_MSG_ID_DATA_STREAM 67 - -typedef struct __mavlink_data_stream_t -{ - uint16_t message_rate; ///< The requested interval between two messages of this type - uint8_t stream_id; ///< The ID of the requested data stream - uint8_t on_off; ///< 1 stream is enabled, 0 stream is stopped. -} mavlink_data_stream_t; - -#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4 -#define MAVLINK_MSG_ID_67_LEN 4 - -#define MAVLINK_MSG_ID_DATA_STREAM_CRC 21 -#define MAVLINK_MSG_ID_67_CRC 21 - - - -#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \ - "DATA_STREAM", \ - 3, \ - { { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \ - { "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \ - { "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \ - } \ -} - - -/** - * @brief Pack a data_stream message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param stream_id The ID of the requested data stream - * @param message_rate The requested interval between two messages of this type - * @param on_off 1 stream is enabled, 0 stream is stopped. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t stream_id, uint16_t message_rate, uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, message_rate); - _mav_put_uint8_t(buf, 2, stream_id); - _mav_put_uint8_t(buf, 3, on_off); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#else - mavlink_data_stream_t packet; - packet.message_rate = message_rate; - packet.stream_id = stream_id; - packet.on_off = on_off; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif -} - -/** - * @brief Pack a data_stream message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param stream_id The ID of the requested data stream - * @param message_rate The requested interval between two messages of this type - * @param on_off 1 stream is enabled, 0 stream is stopped. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t stream_id,uint16_t message_rate,uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, message_rate); - _mav_put_uint8_t(buf, 2, stream_id); - _mav_put_uint8_t(buf, 3, on_off); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#else - mavlink_data_stream_t packet; - packet.message_rate = message_rate; - packet.stream_id = stream_id; - packet.on_off = on_off; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_STREAM; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif -} - -/** - * @brief Encode a data_stream struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) -{ - return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -} - -/** - * @brief Encode a data_stream struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream) -{ - return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off); -} - -/** - * @brief Send a data_stream message - * @param chan MAVLink channel to send the message - * - * @param stream_id The ID of the requested data stream - * @param message_rate The requested interval between two messages of this type - * @param on_off 1 stream is enabled, 0 stream is stopped. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, message_rate); - _mav_put_uint8_t(buf, 2, stream_id); - _mav_put_uint8_t(buf, 3, on_off); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif -#else - mavlink_data_stream_t packet; - packet.message_rate = message_rate; - packet.stream_id = stream_id; - packet.on_off = on_off; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, message_rate); - _mav_put_uint8_t(buf, 2, stream_id); - _mav_put_uint8_t(buf, 3, on_off); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif -#else - mavlink_data_stream_t *packet = (mavlink_data_stream_t *)msgbuf; - packet->message_rate = message_rate; - packet->stream_id = stream_id; - packet->on_off = on_off; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DATA_STREAM UNPACKING - - -/** - * @brief Get field stream_id from data_stream message - * - * @return The ID of the requested data stream - */ -static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field message_rate from data_stream message - * - * @return The requested interval between two messages of this type - */ -static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field on_off from data_stream message - * - * @return 1 stream is enabled, 0 stream is stopped. - */ -static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Decode a data_stream message into a struct - * - * @param msg The message to decode - * @param data_stream C-struct to decode the message contents into - */ -static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP - data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(msg); - data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg); - data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg); -#else - memcpy(data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_STREAM_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h deleted file mode 100644 index d84a73709..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_data_transmission_handshake.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130 - -typedef struct __mavlink_data_transmission_handshake_t -{ - uint32_t size; ///< total data size in bytes (set on ACK only) - uint16_t width; ///< Width of a matrix or image - uint16_t height; ///< Height of a matrix or image - uint16_t packets; ///< number of packets beeing sent (set on ACK only) - uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - uint8_t jpg_quality; ///< JPEG quality out of [1,100] -} mavlink_data_transmission_handshake_t; - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13 -#define MAVLINK_MSG_ID_130_LEN 13 - -#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29 -#define MAVLINK_MSG_ID_130_CRC 29 - - - -#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \ - "DATA_TRANSMISSION_HANDSHAKE", \ - 7, \ - { { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \ - { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \ - { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \ - { "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \ - { "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \ - { "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \ - } \ -} - - -/** - * @brief Pack a data_transmission_handshake message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif -} - -/** - * @brief Pack a data_transmission_handshake message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint16_t packets,uint8_t payload,uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif -} - -/** - * @brief Encode a data_transmission_handshake struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param data_transmission_handshake C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ - return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -} - -/** - * @brief Encode a data_transmission_handshake struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param data_transmission_handshake C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ - return mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, chan, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality); -} - -/** - * @brief Send a data_transmission_handshake message - * @param chan MAVLink channel to send the message - * - * @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - * @param size total data size in bytes (set on ACK only) - * @param width Width of a matrix or image - * @param height Height of a matrix or image - * @param packets number of packets beeing sent (set on ACK only) - * @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - * @param jpg_quality JPEG quality out of [1,100] - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN]; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif -#else - mavlink_data_transmission_handshake_t packet; - packet.size = size; - packet.width = width; - packet.height = height; - packet.packets = packets; - packet.type = type; - packet.payload = payload; - packet.jpg_quality = jpg_quality; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, size); - _mav_put_uint16_t(buf, 4, width); - _mav_put_uint16_t(buf, 6, height); - _mav_put_uint16_t(buf, 8, packets); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, payload); - _mav_put_uint8_t(buf, 12, jpg_quality); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif -#else - mavlink_data_transmission_handshake_t *packet = (mavlink_data_transmission_handshake_t *)msgbuf; - packet->size = size; - packet->width = width; - packet->height = height; - packet->packets = packets; - packet->type = type; - packet->payload = payload; - packet->jpg_quality = jpg_quality; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING - - -/** - * @brief Get field type from data_transmission_handshake message - * - * @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h) - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field size from data_transmission_handshake message - * - * @return total data size in bytes (set on ACK only) - */ -static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field width from data_transmission_handshake message - * - * @return Width of a matrix or image - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field height from data_transmission_handshake message - * - * @return Height of a matrix or image - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field packets from data_transmission_handshake message - * - * @return number of packets beeing sent (set on ACK only) - */ -static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field payload from data_transmission_handshake message - * - * @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only) - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field jpg_quality from data_transmission_handshake message - * - * @return JPEG quality out of [1,100] - */ -static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Decode a data_transmission_handshake message into a struct - * - * @param msg The message to decode - * @param data_transmission_handshake C-struct to decode the message contents into - */ -static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake) -{ -#if MAVLINK_NEED_BYTE_SWAP - data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg); - data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg); - data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg); - data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg); - data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg); - data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg); - data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg); -#else - memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h deleted file mode 100644 index 2102af862..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE DEBUG PACKING - -#define MAVLINK_MSG_ID_DEBUG 254 - -typedef struct __mavlink_debug_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - float value; ///< DEBUG value - uint8_t ind; ///< index of debug variable -} mavlink_debug_t; - -#define MAVLINK_MSG_ID_DEBUG_LEN 9 -#define MAVLINK_MSG_ID_254_LEN 9 - -#define MAVLINK_MSG_ID_DEBUG_CRC 46 -#define MAVLINK_MSG_ID_254_CRC 46 - - - -#define MAVLINK_MESSAGE_INFO_DEBUG { \ - "DEBUG", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \ - { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \ - } \ -} - - -/** - * @brief Pack a debug message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_uint8_t(buf, 8, ind); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); -#else - mavlink_debug_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - packet.ind = ind; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN); -#endif -} - -/** - * @brief Pack a debug message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t ind,float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_uint8_t(buf, 8, ind); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_LEN); -#else - mavlink_debug_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - packet.ind = ind; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN); -#endif -} - -/** - * @brief Encode a debug struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param debug C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug) -{ - return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value); -} - -/** - * @brief Encode a debug struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param debug C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug) -{ - return mavlink_msg_debug_pack_chan(system_id, component_id, chan, msg, debug->time_boot_ms, debug->ind, debug->value); -} - -/** - * @brief Send a debug message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param ind index of debug variable - * @param value DEBUG value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_uint8_t(buf, 8, ind); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN); -#endif -#else - mavlink_debug_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - packet.ind = ind; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DEBUG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_uint8_t(buf, 8, ind); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN); -#endif -#else - mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->value = value; - packet->ind = ind; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DEBUG UNPACKING - - -/** - * @brief Get field time_boot_ms from debug message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field ind from debug message - * - * @return index of debug variable - */ -static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field value from debug message - * - * @return DEBUG value - */ -static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a debug message into a struct - * - * @param msg The message to decode - * @param debug C-struct to decode the message contents into - */ -static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug) -{ -#if MAVLINK_NEED_BYTE_SWAP - debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg); - debug->value = mavlink_msg_debug_get_value(msg); - debug->ind = mavlink_msg_debug_get_ind(msg); -#else - memcpy(debug, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h deleted file mode 100644 index 67c339e89..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h +++ /dev/null @@ -1,297 +0,0 @@ -// MESSAGE DEBUG_VECT PACKING - -#define MAVLINK_MSG_ID_DEBUG_VECT 250 - -typedef struct __mavlink_debug_vect_t -{ - uint64_t time_usec; ///< Timestamp - float x; ///< x - float y; ///< y - float z; ///< z - char name[10]; ///< Name -} mavlink_debug_vect_t; - -#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30 -#define MAVLINK_MSG_ID_250_LEN 30 - -#define MAVLINK_MSG_ID_DEBUG_VECT_CRC 49 -#define MAVLINK_MSG_ID_250_CRC 49 - -#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10 - -#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \ - "DEBUG_VECT", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \ - } \ -} - - -/** - * @brief Pack a debug_vect message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *name, uint64_t time_usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_char_array(buf, 20, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif -} - -/** - * @brief Pack a debug_vect message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *name,uint64_t time_usec,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_char_array(buf, 20, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif -} - -/** - * @brief Encode a debug_vect struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param debug_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) -{ - return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -} - -/** - * @brief Encode a debug_vect struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param debug_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_debug_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect) -{ - return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z); -} - -/** - * @brief Send a debug_vect message - * @param chan MAVLink channel to send the message - * - * @param name Name - * @param time_usec Timestamp - * @param x x - * @param y y - * @param z z - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DEBUG_VECT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_char_array(buf, 20, name, 10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif -#else - mavlink_debug_vect_t packet; - packet.time_usec = time_usec; - packet.x = x; - packet.y = y; - packet.z = z; - mav_array_memcpy(packet.name, name, sizeof(char)*10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_char_array(buf, 20, name, 10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif -#else - mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf; - packet->time_usec = time_usec; - packet->x = x; - packet->y = y; - packet->z = z; - mav_array_memcpy(packet->name, name, sizeof(char)*10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DEBUG_VECT UNPACKING - - -/** - * @brief Get field name from debug_vect message - * - * @return Name - */ -static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 20); -} - -/** - * @brief Get field time_usec from debug_vect message - * - * @return Timestamp - */ -static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from debug_vect message - * - * @return x - */ -static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from debug_vect message - * - * @return y - */ -static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from debug_vect message - * - * @return z - */ -static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a debug_vect message into a struct - * - * @param msg The message to decode - * @param debug_vect C-struct to decode the message contents into - */ -static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP - debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg); - debug_vect->x = mavlink_msg_debug_vect_get_x(msg); - debug_vect->y = mavlink_msg_debug_vect_get_y(msg); - debug_vect->z = mavlink_msg_debug_vect_get_z(msg); - mavlink_msg_debug_vect_get_name(msg, debug_vect->name); -#else - memcpy(debug_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DEBUG_VECT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h deleted file mode 100644 index 39b384396..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_distance_sensor.h +++ /dev/null @@ -1,377 +0,0 @@ -// MESSAGE DISTANCE_SENSOR PACKING - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132 - -typedef struct __mavlink_distance_sensor_t -{ - uint32_t time_boot_ms; ///< Time since system boot - uint16_t min_distance; ///< Minimum distance the sensor can measure in centimeters - uint16_t max_distance; ///< Maximum distance the sensor can measure in centimeters - uint16_t current_distance; ///< Current distance reading - uint8_t type; ///< Type from MAV_DISTANCE_SENSOR enum. - uint8_t id; ///< Onboard ID of the sensor - uint8_t orientation; ///< Direction the sensor faces from FIXME enum. - uint8_t covariance; ///< Measurement covariance in centimeters, 0 for unknown / invalid readings -} mavlink_distance_sensor_t; - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14 -#define MAVLINK_MSG_ID_132_LEN 14 - -#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85 -#define MAVLINK_MSG_ID_132_CRC 85 - - - -#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \ - "DISTANCE_SENSOR", \ - 8, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \ - { "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \ - { "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \ - { "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \ - { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \ - { "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \ - { "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \ - } \ -} - - -/** - * @brief Pack a distance_sensor message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Time since system boot - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from FIXME enum. - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t type, uint8_t id, uint8_t orientation, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif -} - -/** - * @brief Pack a distance_sensor message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Time since system boot - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from FIXME enum. - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t type,uint8_t id,uint8_t orientation,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif -} - -/** - * @brief Encode a distance_sensor struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param distance_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) -{ - return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->covariance); -} - -/** - * @brief Encode a distance_sensor struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param distance_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor) -{ - return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->covariance); -} - -/** - * @brief Send a distance_sensor message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Time since system boot - * @param type Type from MAV_DISTANCE_SENSOR enum. - * @param id Onboard ID of the sensor - * @param orientation Direction the sensor faces from FIXME enum. - * @param min_distance Minimum distance the sensor can measure in centimeters - * @param max_distance Maximum distance the sensor can measure in centimeters - * @param current_distance Current distance reading - * @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type, uint8_t id, uint8_t orientation, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif -#else - mavlink_distance_sensor_t packet; - packet.time_boot_ms = time_boot_ms; - packet.min_distance = min_distance; - packet.max_distance = max_distance; - packet.current_distance = current_distance; - packet.type = type; - packet.id = id; - packet.orientation = orientation; - packet.covariance = covariance; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type, uint8_t id, uint8_t orientation, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t covariance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, min_distance); - _mav_put_uint16_t(buf, 6, max_distance); - _mav_put_uint16_t(buf, 8, current_distance); - _mav_put_uint8_t(buf, 10, type); - _mav_put_uint8_t(buf, 11, id); - _mav_put_uint8_t(buf, 12, orientation); - _mav_put_uint8_t(buf, 13, covariance); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif -#else - mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->min_distance = min_distance; - packet->max_distance = max_distance; - packet->current_distance = current_distance; - packet->type = type; - packet->id = id; - packet->orientation = orientation; - packet->covariance = covariance; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE DISTANCE_SENSOR UNPACKING - - -/** - * @brief Get field time_boot_ms from distance_sensor message - * - * @return Time since system boot - */ -static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field type from distance_sensor message - * - * @return Type from MAV_DISTANCE_SENSOR enum. - */ -static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field id from distance_sensor message - * - * @return Onboard ID of the sensor - */ -static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field orientation from distance_sensor message - * - * @return Direction the sensor faces from FIXME enum. - */ -static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field min_distance from distance_sensor message - * - * @return Minimum distance the sensor can measure in centimeters - */ -static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field max_distance from distance_sensor message - * - * @return Maximum distance the sensor can measure in centimeters - */ -static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field current_distance from distance_sensor message - * - * @return Current distance reading - */ -static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field covariance from distance_sensor message - * - * @return Measurement covariance in centimeters, 0 for unknown / invalid readings - */ -static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Decode a distance_sensor message into a struct - * - * @param msg The message to decode - * @param distance_sensor C-struct to decode the message contents into - */ -static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP - distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg); - distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg); - distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg); - distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg); - distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg); - distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg); - distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg); - distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg); -#else - memcpy(distance_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h deleted file mode 100644 index dacd7c9f4..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_encapsulated_data.h +++ /dev/null @@ -1,225 +0,0 @@ -// MESSAGE ENCAPSULATED_DATA PACKING - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131 - -typedef struct __mavlink_encapsulated_data_t -{ - uint16_t seqnr; ///< sequence number (starting with 0 on every transmission) - uint8_t data[253]; ///< image data bytes -} mavlink_encapsulated_data_t; - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255 -#define MAVLINK_MSG_ID_131_LEN 255 - -#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223 -#define MAVLINK_MSG_ID_131_CRC 223 - -#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253 - -#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \ - "ENCAPSULATED_DATA", \ - 2, \ - { { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \ - } \ -} - - -/** - * @brief Pack a encapsulated_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; - _mav_put_uint16_t(buf, 0, seqnr); - _mav_put_uint8_t_array(buf, 2, data, 253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#else - mavlink_encapsulated_data_t packet; - packet.seqnr = seqnr; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif -} - -/** - * @brief Pack a encapsulated_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seqnr,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; - _mav_put_uint16_t(buf, 0, seqnr); - _mav_put_uint8_t_array(buf, 2, data, 253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#else - mavlink_encapsulated_data_t packet; - packet.seqnr = seqnr; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif -} - -/** - * @brief Encode a encapsulated_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param encapsulated_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) -{ - return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data); -} - -/** - * @brief Encode a encapsulated_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param encapsulated_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_encapsulated_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data) -{ - return mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, chan, msg, encapsulated_data->seqnr, encapsulated_data->data); -} - -/** - * @brief Send a encapsulated_data message - * @param chan MAVLink channel to send the message - * - * @param seqnr sequence number (starting with 0 on every transmission) - * @param data image data bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN]; - _mav_put_uint16_t(buf, 0, seqnr); - _mav_put_uint8_t_array(buf, 2, data, 253); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif -#else - mavlink_encapsulated_data_t packet; - packet.seqnr = seqnr; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_encapsulated_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seqnr); - _mav_put_uint8_t_array(buf, 2, data, 253); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif -#else - mavlink_encapsulated_data_t *packet = (mavlink_encapsulated_data_t *)msgbuf; - packet->seqnr = seqnr; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*253); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE ENCAPSULATED_DATA UNPACKING - - -/** - * @brief Get field seqnr from encapsulated_data message - * - * @return sequence number (starting with 0 on every transmission) - */ -static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field data from encapsulated_data message - * - * @return image data bytes - */ -static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 253, 2); -} - -/** - * @brief Decode a encapsulated_data message into a struct - * - * @param msg The message to decode - * @param encapsulated_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data) -{ -#if MAVLINK_NEED_BYTE_SWAP - encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg); - mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data); -#else - memcpy(encapsulated_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h deleted file mode 100644 index 81c7031ce..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_dir_list.h +++ /dev/null @@ -1,249 +0,0 @@ -// MESSAGE FILE_TRANSFER_DIR_LIST PACKING - -#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST 111 - -typedef struct __mavlink_file_transfer_dir_list_t -{ - uint64_t transfer_uid; ///< Unique transfer ID - char dir_path[240]; ///< Directory path to list - uint8_t flags; ///< RESERVED -} mavlink_file_transfer_dir_list_t; - -#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN 249 -#define MAVLINK_MSG_ID_111_LEN 249 - -#define MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC 93 -#define MAVLINK_MSG_ID_111_CRC 93 - -#define MAVLINK_MSG_FILE_TRANSFER_DIR_LIST_FIELD_DIR_PATH_LEN 240 - -#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST { \ - "FILE_TRANSFER_DIR_LIST", \ - 3, \ - { { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_dir_list_t, transfer_uid) }, \ - { "dir_path", NULL, MAVLINK_TYPE_CHAR, 240, 8, offsetof(mavlink_file_transfer_dir_list_t, dir_path) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 248, offsetof(mavlink_file_transfer_dir_list_t, flags) }, \ - } \ -} - - -/** - * @brief Pack a file_transfer_dir_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param transfer_uid Unique transfer ID - * @param dir_path Directory path to list - * @param flags RESERVED - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_dir_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t transfer_uid, const char *dir_path, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN]; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint8_t(buf, 248, flags); - _mav_put_char_array(buf, 8, dir_path, 240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#else - mavlink_file_transfer_dir_list_t packet; - packet.transfer_uid = transfer_uid; - packet.flags = flags; - mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#endif -} - -/** - * @brief Pack a file_transfer_dir_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param transfer_uid Unique transfer ID - * @param dir_path Directory path to list - * @param flags RESERVED - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_dir_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t transfer_uid,const char *dir_path,uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN]; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint8_t(buf, 248, flags); - _mav_put_char_array(buf, 8, dir_path, 240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#else - mavlink_file_transfer_dir_list_t packet; - packet.transfer_uid = transfer_uid; - packet.flags = flags; - mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#endif -} - -/** - * @brief Encode a file_transfer_dir_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param file_transfer_dir_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_dir_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_dir_list_t* file_transfer_dir_list) -{ - return mavlink_msg_file_transfer_dir_list_pack(system_id, component_id, msg, file_transfer_dir_list->transfer_uid, file_transfer_dir_list->dir_path, file_transfer_dir_list->flags); -} - -/** - * @brief Encode a file_transfer_dir_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param file_transfer_dir_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_dir_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_dir_list_t* file_transfer_dir_list) -{ - return mavlink_msg_file_transfer_dir_list_pack_chan(system_id, component_id, chan, msg, file_transfer_dir_list->transfer_uid, file_transfer_dir_list->dir_path, file_transfer_dir_list->flags); -} - -/** - * @brief Send a file_transfer_dir_list message - * @param chan MAVLink channel to send the message - * - * @param transfer_uid Unique transfer ID - * @param dir_path Directory path to list - * @param flags RESERVED - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_file_transfer_dir_list_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dir_path, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN]; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint8_t(buf, 248, flags); - _mav_put_char_array(buf, 8, dir_path, 240); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#endif -#else - mavlink_file_transfer_dir_list_t packet; - packet.transfer_uid = transfer_uid; - packet.flags = flags; - mav_array_memcpy(packet.dir_path, dir_path, sizeof(char)*240); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_file_transfer_dir_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t transfer_uid, const char *dir_path, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint8_t(buf, 248, flags); - _mav_put_char_array(buf, 8, dir_path, 240); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, buf, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#endif -#else - mavlink_file_transfer_dir_list_t *packet = (mavlink_file_transfer_dir_list_t *)msgbuf; - packet->transfer_uid = transfer_uid; - packet->flags = flags; - mav_array_memcpy(packet->dir_path, dir_path, sizeof(char)*240); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FILE_TRANSFER_DIR_LIST UNPACKING - - -/** - * @brief Get field transfer_uid from file_transfer_dir_list message - * - * @return Unique transfer ID - */ -static inline uint64_t mavlink_msg_file_transfer_dir_list_get_transfer_uid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field dir_path from file_transfer_dir_list message - * - * @return Directory path to list - */ -static inline uint16_t mavlink_msg_file_transfer_dir_list_get_dir_path(const mavlink_message_t* msg, char *dir_path) -{ - return _MAV_RETURN_char_array(msg, dir_path, 240, 8); -} - -/** - * @brief Get field flags from file_transfer_dir_list message - * - * @return RESERVED - */ -static inline uint8_t mavlink_msg_file_transfer_dir_list_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 248); -} - -/** - * @brief Decode a file_transfer_dir_list message into a struct - * - * @param msg The message to decode - * @param file_transfer_dir_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_file_transfer_dir_list_decode(const mavlink_message_t* msg, mavlink_file_transfer_dir_list_t* file_transfer_dir_list) -{ -#if MAVLINK_NEED_BYTE_SWAP - file_transfer_dir_list->transfer_uid = mavlink_msg_file_transfer_dir_list_get_transfer_uid(msg); - mavlink_msg_file_transfer_dir_list_get_dir_path(msg, file_transfer_dir_list->dir_path); - file_transfer_dir_list->flags = mavlink_msg_file_transfer_dir_list_get_flags(msg); -#else - memcpy(file_transfer_dir_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_DIR_LIST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h deleted file mode 100644 index 04981fa85..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_res.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE FILE_TRANSFER_RES PACKING - -#define MAVLINK_MSG_ID_FILE_TRANSFER_RES 112 - -typedef struct __mavlink_file_transfer_res_t -{ - uint64_t transfer_uid; ///< Unique transfer ID - uint8_t result; ///< 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device -} mavlink_file_transfer_res_t; - -#define MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN 9 -#define MAVLINK_MSG_ID_112_LEN 9 - -#define MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC 124 -#define MAVLINK_MSG_ID_112_CRC 124 - - - -#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES { \ - "FILE_TRANSFER_RES", \ - 2, \ - { { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_res_t, transfer_uid) }, \ - { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_file_transfer_res_t, result) }, \ - } \ -} - - -/** - * @brief Pack a file_transfer_res message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param transfer_uid Unique transfer ID - * @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_res_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t transfer_uid, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN]; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint8_t(buf, 8, result); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#else - mavlink_file_transfer_res_t packet; - packet.transfer_uid = transfer_uid; - packet.result = result; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#endif -} - -/** - * @brief Pack a file_transfer_res message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param transfer_uid Unique transfer ID - * @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_res_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t transfer_uid,uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN]; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint8_t(buf, 8, result); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#else - mavlink_file_transfer_res_t packet; - packet.transfer_uid = transfer_uid; - packet.result = result; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_RES; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#endif -} - -/** - * @brief Encode a file_transfer_res struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param file_transfer_res C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_res_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_res_t* file_transfer_res) -{ - return mavlink_msg_file_transfer_res_pack(system_id, component_id, msg, file_transfer_res->transfer_uid, file_transfer_res->result); -} - -/** - * @brief Encode a file_transfer_res struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param file_transfer_res C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_res_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_res_t* file_transfer_res) -{ - return mavlink_msg_file_transfer_res_pack_chan(system_id, component_id, chan, msg, file_transfer_res->transfer_uid, file_transfer_res->result); -} - -/** - * @brief Send a file_transfer_res message - * @param chan MAVLink channel to send the message - * - * @param transfer_uid Unique transfer ID - * @param result 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_file_transfer_res_send(mavlink_channel_t chan, uint64_t transfer_uid, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN]; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint8_t(buf, 8, result); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#endif -#else - mavlink_file_transfer_res_t packet; - packet.transfer_uid = transfer_uid; - packet.result = result; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_file_transfer_res_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t transfer_uid, uint8_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint8_t(buf, 8, result); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, buf, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#endif -#else - mavlink_file_transfer_res_t *packet = (mavlink_file_transfer_res_t *)msgbuf; - packet->transfer_uid = transfer_uid; - packet->result = result; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_RES_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_RES, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FILE_TRANSFER_RES UNPACKING - - -/** - * @brief Get field transfer_uid from file_transfer_res message - * - * @return Unique transfer ID - */ -static inline uint64_t mavlink_msg_file_transfer_res_get_transfer_uid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field result from file_transfer_res message - * - * @return 0: OK, 1: not permitted, 2: bad path / file name, 3: no space left on device - */ -static inline uint8_t mavlink_msg_file_transfer_res_get_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Decode a file_transfer_res message into a struct - * - * @param msg The message to decode - * @param file_transfer_res C-struct to decode the message contents into - */ -static inline void mavlink_msg_file_transfer_res_decode(const mavlink_message_t* msg, mavlink_file_transfer_res_t* file_transfer_res) -{ -#if MAVLINK_NEED_BYTE_SWAP - file_transfer_res->transfer_uid = mavlink_msg_file_transfer_res_get_transfer_uid(msg); - file_transfer_res->result = mavlink_msg_file_transfer_res_get_result(msg); -#else - memcpy(file_transfer_res, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_RES_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h deleted file mode 100644 index 7b1fba519..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_file_transfer_start.h +++ /dev/null @@ -1,297 +0,0 @@ -// MESSAGE FILE_TRANSFER_START PACKING - -#define MAVLINK_MSG_ID_FILE_TRANSFER_START 110 - -typedef struct __mavlink_file_transfer_start_t -{ - uint64_t transfer_uid; ///< Unique transfer ID - uint32_t file_size; ///< File size in bytes - char dest_path[240]; ///< Destination path - uint8_t direction; ///< Transfer direction: 0: from requester, 1: to requester - uint8_t flags; ///< RESERVED -} mavlink_file_transfer_start_t; - -#define MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN 254 -#define MAVLINK_MSG_ID_110_LEN 254 - -#define MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC 235 -#define MAVLINK_MSG_ID_110_CRC 235 - -#define MAVLINK_MSG_FILE_TRANSFER_START_FIELD_DEST_PATH_LEN 240 - -#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START { \ - "FILE_TRANSFER_START", \ - 5, \ - { { "transfer_uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_file_transfer_start_t, transfer_uid) }, \ - { "file_size", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_file_transfer_start_t, file_size) }, \ - { "dest_path", NULL, MAVLINK_TYPE_CHAR, 240, 12, offsetof(mavlink_file_transfer_start_t, dest_path) }, \ - { "direction", NULL, MAVLINK_TYPE_UINT8_T, 0, 252, offsetof(mavlink_file_transfer_start_t, direction) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 253, offsetof(mavlink_file_transfer_start_t, flags) }, \ - } \ -} - - -/** - * @brief Pack a file_transfer_start message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param transfer_uid Unique transfer ID - * @param dest_path Destination path - * @param direction Transfer direction: 0: from requester, 1: to requester - * @param file_size File size in bytes - * @param flags RESERVED - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_start_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN]; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint32_t(buf, 8, file_size); - _mav_put_uint8_t(buf, 252, direction); - _mav_put_uint8_t(buf, 253, flags); - _mav_put_char_array(buf, 12, dest_path, 240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#else - mavlink_file_transfer_start_t packet; - packet.transfer_uid = transfer_uid; - packet.file_size = file_size; - packet.direction = direction; - packet.flags = flags; - mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#endif -} - -/** - * @brief Pack a file_transfer_start message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param transfer_uid Unique transfer ID - * @param dest_path Destination path - * @param direction Transfer direction: 0: from requester, 1: to requester - * @param file_size File size in bytes - * @param flags RESERVED - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_file_transfer_start_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t transfer_uid,const char *dest_path,uint8_t direction,uint32_t file_size,uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN]; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint32_t(buf, 8, file_size); - _mav_put_uint8_t(buf, 252, direction); - _mav_put_uint8_t(buf, 253, flags); - _mav_put_char_array(buf, 12, dest_path, 240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#else - mavlink_file_transfer_start_t packet; - packet.transfer_uid = transfer_uid; - packet.file_size = file_size; - packet.direction = direction; - packet.flags = flags; - mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_START; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#endif -} - -/** - * @brief Encode a file_transfer_start struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param file_transfer_start C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_start_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_start_t* file_transfer_start) -{ - return mavlink_msg_file_transfer_start_pack(system_id, component_id, msg, file_transfer_start->transfer_uid, file_transfer_start->dest_path, file_transfer_start->direction, file_transfer_start->file_size, file_transfer_start->flags); -} - -/** - * @brief Encode a file_transfer_start struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param file_transfer_start C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_file_transfer_start_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_start_t* file_transfer_start) -{ - return mavlink_msg_file_transfer_start_pack_chan(system_id, component_id, chan, msg, file_transfer_start->transfer_uid, file_transfer_start->dest_path, file_transfer_start->direction, file_transfer_start->file_size, file_transfer_start->flags); -} - -/** - * @brief Send a file_transfer_start message - * @param chan MAVLink channel to send the message - * - * @param transfer_uid Unique transfer ID - * @param dest_path Destination path - * @param direction Transfer direction: 0: from requester, 1: to requester - * @param file_size File size in bytes - * @param flags RESERVED - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_file_transfer_start_send(mavlink_channel_t chan, uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN]; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint32_t(buf, 8, file_size); - _mav_put_uint8_t(buf, 252, direction); - _mav_put_uint8_t(buf, 253, flags); - _mav_put_char_array(buf, 12, dest_path, 240); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#endif -#else - mavlink_file_transfer_start_t packet; - packet.transfer_uid = transfer_uid; - packet.file_size = file_size; - packet.direction = direction; - packet.flags = flags; - mav_array_memcpy(packet.dest_path, dest_path, sizeof(char)*240); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_file_transfer_start_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t transfer_uid, const char *dest_path, uint8_t direction, uint32_t file_size, uint8_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, transfer_uid); - _mav_put_uint32_t(buf, 8, file_size); - _mav_put_uint8_t(buf, 252, direction); - _mav_put_uint8_t(buf, 253, flags); - _mav_put_char_array(buf, 12, dest_path, 240); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, buf, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#endif -#else - mavlink_file_transfer_start_t *packet = (mavlink_file_transfer_start_t *)msgbuf; - packet->transfer_uid = transfer_uid; - packet->file_size = file_size; - packet->direction = direction; - packet->flags = flags; - mav_array_memcpy(packet->dest_path, dest_path, sizeof(char)*240); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_START_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_START, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FILE_TRANSFER_START UNPACKING - - -/** - * @brief Get field transfer_uid from file_transfer_start message - * - * @return Unique transfer ID - */ -static inline uint64_t mavlink_msg_file_transfer_start_get_transfer_uid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field dest_path from file_transfer_start message - * - * @return Destination path - */ -static inline uint16_t mavlink_msg_file_transfer_start_get_dest_path(const mavlink_message_t* msg, char *dest_path) -{ - return _MAV_RETURN_char_array(msg, dest_path, 240, 12); -} - -/** - * @brief Get field direction from file_transfer_start message - * - * @return Transfer direction: 0: from requester, 1: to requester - */ -static inline uint8_t mavlink_msg_file_transfer_start_get_direction(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 252); -} - -/** - * @brief Get field file_size from file_transfer_start message - * - * @return File size in bytes - */ -static inline uint32_t mavlink_msg_file_transfer_start_get_file_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field flags from file_transfer_start message - * - * @return RESERVED - */ -static inline uint8_t mavlink_msg_file_transfer_start_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 253); -} - -/** - * @brief Decode a file_transfer_start message into a struct - * - * @param msg The message to decode - * @param file_transfer_start C-struct to decode the message contents into - */ -static inline void mavlink_msg_file_transfer_start_decode(const mavlink_message_t* msg, mavlink_file_transfer_start_t* file_transfer_start) -{ -#if MAVLINK_NEED_BYTE_SWAP - file_transfer_start->transfer_uid = mavlink_msg_file_transfer_start_get_transfer_uid(msg); - file_transfer_start->file_size = mavlink_msg_file_transfer_start_get_file_size(msg); - mavlink_msg_file_transfer_start_get_dest_path(msg, file_transfer_start->dest_path); - file_transfer_start->direction = mavlink_msg_file_transfer_start_get_direction(msg); - file_transfer_start->flags = mavlink_msg_file_transfer_start_get_flags(msg); -#else - memcpy(file_transfer_start, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_START_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h deleted file mode 100644 index ba15bf365..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h +++ /dev/null @@ -1,401 +0,0 @@ -// MESSAGE GLOBAL_POSITION_INT PACKING - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33 - -typedef struct __mavlink_global_position_int_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - int32_t lat; ///< Latitude, expressed as * 1E7 - int32_t lon; ///< Longitude, expressed as * 1E7 - int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL - int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters) - int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 - int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 - int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 - uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX -} mavlink_global_position_int_t; - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28 -#define MAVLINK_MSG_ID_33_LEN 28 - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104 -#define MAVLINK_MSG_ID_33_CRC 104 - - - -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \ - "GLOBAL_POSITION_INT", \ - 9, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \ - { "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \ - { "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \ - } \ -} - - -/** - * @brief Pack a global_position_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#else - mavlink_global_position_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif -} - -/** - * @brief Pack a global_position_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#else - mavlink_global_position_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif -} - -/** - * @brief Encode a global_position_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_position_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) -{ - return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -} - -/** - * @brief Encode a global_position_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_position_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int) -{ - return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg); -} - -/** - * @brief Send a global_position_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif -#else - mavlink_global_position_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.relative_alt = relative_alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.hdg = hdg; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, lon); - _mav_put_int32_t(buf, 12, alt); - _mav_put_int32_t(buf, 16, relative_alt); - _mav_put_int16_t(buf, 20, vx); - _mav_put_int16_t(buf, 22, vy); - _mav_put_int16_t(buf, 24, vz); - _mav_put_uint16_t(buf, 26, hdg); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif -#else - mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->relative_alt = relative_alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->hdg = hdg; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_POSITION_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from global_position_int message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field lat from global_position_int message - * - * @return Latitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field lon from global_position_int message - * - * @return Longitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt from global_position_int message - * - * @return Altitude in meters, expressed as * 1000 (millimeters), above MSL - */ -static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field relative_alt from global_position_int message - * - * @return Altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field vx from global_position_int message - * - * @return Ground X Speed (Latitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field vy from global_position_int message - * - * @return Ground Y Speed (Longitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field vz from global_position_int message - * - * @return Ground Z Speed (Altitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Get field hdg from global_position_int message - * - * @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Decode a global_position_int message into a struct - * - * @param msg The message to decode - * @param global_position_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int) -{ -#if MAVLINK_NEED_BYTE_SWAP - global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg); - global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg); - global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg); - global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg); - global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg); - global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg); - global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg); - global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg); - global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg); -#else - memcpy(global_position_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h deleted file mode 100644 index 77d735cf4..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE GLOBAL_POSITION_SETPOINT_INT PACKING - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT 52 - -typedef struct __mavlink_global_position_setpoint_int_t -{ - int32_t latitude; ///< Latitude (WGS84), in degrees * 1E7 - int32_t longitude; ///< Longitude (WGS84), in degrees * 1E7 - int32_t altitude; ///< Altitude (WGS84), in meters * 1000 (positive for up) - int16_t yaw; ///< Desired yaw angle in degrees * 100 - uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT -} mavlink_global_position_setpoint_int_t; - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15 -#define MAVLINK_MSG_ID_52_LEN 15 - -#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC 141 -#define MAVLINK_MSG_ID_52_CRC 141 - - - -#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT { \ - "GLOBAL_POSITION_SETPOINT_INT", \ - 5, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_setpoint_int_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_setpoint_int_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_setpoint_int_t, altitude) }, \ - { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_setpoint_int_t, yaw) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_global_position_setpoint_int_t, coordinate_frame) }, \ - } \ -} - - -/** - * @brief Pack a global_position_setpoint_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @param yaw Desired yaw angle in degrees * 100 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_int16_t(buf, 12, yaw); - _mav_put_uint8_t(buf, 14, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#else - mavlink_global_position_setpoint_int_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.yaw = yaw; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -} - -/** - * @brief Pack a global_position_setpoint_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @param yaw Desired yaw angle in degrees * 100 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_int16_t(buf, 12, yaw); - _mav_put_uint8_t(buf, 14, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#else - mavlink_global_position_setpoint_int_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.yaw = yaw; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -} - -/** - * @brief Encode a global_position_setpoint_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_position_setpoint_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_setpoint_int_t* global_position_setpoint_int) -{ - return mavlink_msg_global_position_setpoint_int_pack(system_id, component_id, msg, global_position_setpoint_int->coordinate_frame, global_position_setpoint_int->latitude, global_position_setpoint_int->longitude, global_position_setpoint_int->altitude, global_position_setpoint_int->yaw); -} - -/** - * @brief Encode a global_position_setpoint_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_position_setpoint_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_position_setpoint_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_setpoint_int_t* global_position_setpoint_int) -{ - return mavlink_msg_global_position_setpoint_int_pack_chan(system_id, component_id, chan, msg, global_position_setpoint_int->coordinate_frame, global_position_setpoint_int->latitude, global_position_setpoint_int->longitude, global_position_setpoint_int->altitude, global_position_setpoint_int->yaw); -} - -/** - * @brief Send a global_position_setpoint_int message - * @param chan MAVLink channel to send the message - * - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @param yaw Desired yaw angle in degrees * 100 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_int16_t(buf, 12, yaw); - _mav_put_uint8_t(buf, 14, coordinate_frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -#else - mavlink_global_position_setpoint_int_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.yaw = yaw; - packet.coordinate_frame = coordinate_frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_position_setpoint_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_int16_t(buf, 12, yaw); - _mav_put_uint8_t(buf, 14, coordinate_frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -#else - mavlink_global_position_setpoint_int_t *packet = (mavlink_global_position_setpoint_int_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->yaw = yaw; - packet->coordinate_frame = coordinate_frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_POSITION_SETPOINT_INT UNPACKING - - -/** - * @brief Get field coordinate_frame from global_position_setpoint_int message - * - * @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - */ -static inline uint8_t mavlink_msg_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Get field latitude from global_position_setpoint_int message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from global_position_setpoint_int message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from global_position_setpoint_int message - * - * @return Altitude (WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field yaw from global_position_setpoint_int message - * - * @return Desired yaw angle in degrees * 100 - */ -static inline int16_t mavlink_msg_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Decode a global_position_setpoint_int message into a struct - * - * @param msg The message to decode - * @param global_position_setpoint_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_position_setpoint_int_decode(const mavlink_message_t* msg, mavlink_global_position_setpoint_int_t* global_position_setpoint_int) -{ -#if MAVLINK_NEED_BYTE_SWAP - global_position_setpoint_int->latitude = mavlink_msg_global_position_setpoint_int_get_latitude(msg); - global_position_setpoint_int->longitude = mavlink_msg_global_position_setpoint_int_get_longitude(msg); - global_position_setpoint_int->altitude = mavlink_msg_global_position_setpoint_int_get_altitude(msg); - global_position_setpoint_int->yaw = mavlink_msg_global_position_setpoint_int_get_yaw(msg); - global_position_setpoint_int->coordinate_frame = mavlink_msg_global_position_setpoint_int_get_coordinate_frame(msg); -#else - memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h deleted file mode 100644 index b2b75d7ef..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101 - -typedef struct __mavlink_global_vision_position_estimate_t -{ - uint64_t usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot) - float x; ///< Global X position - float y; ///< Global Y position - float z; ///< Global Z position - float roll; ///< Roll angle in rad - float pitch; ///< Pitch angle in rad - float yaw; ///< Yaw angle in rad -} mavlink_global_vision_position_estimate_t; - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_101_LEN 32 - -#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102 -#define MAVLINK_MSG_ID_101_CRC 102 - - - -#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \ - "GLOBAL_VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \ - } \ -} - - -/** - * @brief Pack a global_vision_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_global_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif -} - -/** - * @brief Pack a global_vision_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_global_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif -} - -/** - * @brief Encode a global_vision_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param global_vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ - return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); -} - -/** - * @brief Encode a global_vision_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param global_vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ - return mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw); -} - -/** - * @brief Send a global_vision_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif -#else - mavlink_global_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif -#else - mavlink_global_vision_position_estimate_t *packet = (mavlink_global_vision_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from global_vision_position_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from global_vision_position_estimate message - * - * @return Global X position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from global_vision_position_estimate message - * - * @return Global Y position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from global_vision_position_estimate message - * - * @return Global Z position - */ -static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from global_vision_position_estimate message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from global_vision_position_estimate message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from global_vision_position_estimate message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a global_vision_position_estimate message into a struct - * - * @param msg The message to decode - * @param global_vision_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP - global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg); - global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg); - global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg); - global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg); - global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg); - global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg); - global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg); -#else - memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h deleted file mode 100644 index b184e7c9c..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h +++ /dev/null @@ -1,473 +0,0 @@ -// MESSAGE GPS2_RAW PACKING - -#define MAVLINK_MSG_ID_GPS2_RAW 124 - -typedef struct __mavlink_gps2_raw_t -{ - uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - int32_t lat; ///< Latitude (WGS84), in degrees * 1E7 - int32_t lon; ///< Longitude (WGS84), in degrees * 1E7 - int32_t alt; ///< Altitude (WGS84), in meters * 1000 (positive for up) - uint32_t dgps_age; ///< Age of DGPS info - uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255 - uint8_t dgps_numch; ///< Number of DGPS satellites -} mavlink_gps2_raw_t; - -#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35 -#define MAVLINK_MSG_ID_124_LEN 35 - -#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87 -#define MAVLINK_MSG_ID_124_CRC 87 - - - -#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \ - "GPS2_RAW", \ - 12, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \ - { "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \ - { "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \ - } \ -} - - -/** - * @brief Pack a gps2_raw message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif -} - -/** - * @brief Pack a gps2_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible,uint8_t dgps_numch,uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS2_RAW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif -} - -/** - * @brief Encode a gps2_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps2_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) -{ - return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); -} - -/** - * @brief Encode a gps2_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps2_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw) -{ - return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age); -} - -/** - * @brief Send a gps2_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @param dgps_numch Number of DGPS satellites - * @param dgps_age Age of DGPS info - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif -#else - mavlink_gps2_raw_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.dgps_age = dgps_age; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - packet.dgps_numch = dgps_numch; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible, uint8_t dgps_numch, uint32_t dgps_age) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint32_t(buf, 20, dgps_age); - _mav_put_uint16_t(buf, 24, eph); - _mav_put_uint16_t(buf, 26, epv); - _mav_put_uint16_t(buf, 28, vel); - _mav_put_uint16_t(buf, 30, cog); - _mav_put_uint8_t(buf, 32, fix_type); - _mav_put_uint8_t(buf, 33, satellites_visible); - _mav_put_uint8_t(buf, 34, dgps_numch); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif -#else - mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->dgps_age = dgps_age; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - packet->dgps_numch = dgps_numch; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE GPS2_RAW UNPACKING - - -/** - * @brief Get field time_usec from gps2_raw message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from gps2_raw message - * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - */ -static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field lat from gps2_raw message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from gps2_raw message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from gps2_raw message - * - * @return Altitude (WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from gps2_raw message - * - * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field epv from gps2_raw message - * - * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field vel from gps2_raw message - * - * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field cog from gps2_raw message - * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field satellites_visible from gps2_raw message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field dgps_numch from gps2_raw message - * - * @return Number of DGPS satellites - */ -static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field dgps_age from gps2_raw message - * - * @return Age of DGPS info - */ -static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 20); -} - -/** - * @brief Decode a gps2_raw message into a struct - * - * @param msg The message to decode - * @param gps2_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP - gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg); - gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg); - gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg); - gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg); - gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg); - gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg); - gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg); - gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg); - gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg); - gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg); - gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg); - gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg); -#else - memcpy(gps2_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RAW_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h deleted file mode 100644 index 1589c8ca5..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE GPS_GLOBAL_ORIGIN PACKING - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49 - -typedef struct __mavlink_gps_global_origin_t -{ - int32_t latitude; ///< Latitude (WGS84), in degrees * 1E7 - int32_t longitude; ///< Longitude (WGS84), in degrees * 1E7 - int32_t altitude; ///< Altitude (WGS84), in meters * 1000 (positive for up) -} mavlink_gps_global_origin_t; - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12 -#define MAVLINK_MSG_ID_49_LEN 12 - -#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39 -#define MAVLINK_MSG_ID_49_CRC 39 - - - -#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \ - "GPS_GLOBAL_ORIGIN", \ - 3, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \ - } \ -} - - -/** - * @brief Pack a gps_global_origin message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t latitude, int32_t longitude, int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif -} - -/** - * @brief Pack a gps_global_origin message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t latitude,int32_t longitude,int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif -} - -/** - * @brief Encode a gps_global_origin struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) -{ - return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); -} - -/** - * @brief Encode a gps_global_origin struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin) -{ - return mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, chan, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude); -} - -/** - * @brief Send a gps_global_origin message - * @param chan MAVLink channel to send the message - * - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif -#else - mavlink_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif -#else - mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING - - -/** - * @brief Get field latitude from gps_global_origin message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from gps_global_origin message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from gps_global_origin message - * - * @return Altitude (WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Decode a gps_global_origin message into a struct - * - * @param msg The message to decode - * @param gps_global_origin C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP - gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg); - gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg); - gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg); -#else - memcpy(gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h deleted file mode 100644 index 362e2d7b9..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_inject_data.h +++ /dev/null @@ -1,273 +0,0 @@ -// MESSAGE GPS_INJECT_DATA PACKING - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123 - -typedef struct __mavlink_gps_inject_data_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t len; ///< data length - uint8_t data[110]; ///< raw data (110 is enough for 12 satellites of RTCMv2) -} mavlink_gps_inject_data_t; - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 -#define MAVLINK_MSG_ID_123_LEN 113 - -#define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 -#define MAVLINK_MSG_ID_123_CRC 250 - -#define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110 - -#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \ - "GPS_INJECT_DATA", \ - 4, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \ - { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \ - } \ -} - - -/** - * @brief Pack a gps_inject_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif -} - -/** - * @brief Pack a gps_inject_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t len,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif -} - -/** - * @brief Encode a gps_inject_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_inject_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_inject_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) -{ - return mavlink_msg_gps_inject_data_pack(system_id, component_id, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -} - -/** - * @brief Encode a gps_inject_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_inject_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data) -{ - return mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, chan, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data); -} - -/** - * @brief Send a gps_inject_data message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param len data length - * @param data raw data (110 is enough for 12 satellites of RTCMv2) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif -#else - mavlink_gps_inject_data_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.len = len; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, len); - _mav_put_uint8_t_array(buf, 3, data, 110); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif -#else - mavlink_gps_inject_data_t *packet = (mavlink_gps_inject_data_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->len = len; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*110); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE GPS_INJECT_DATA UNPACKING - - -/** - * @brief Get field target_system from gps_inject_data message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from gps_inject_data message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field len from gps_inject_data message - * - * @return data length - */ -static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field data from gps_inject_data message - * - * @return raw data (110 is enough for 12 satellites of RTCMv2) - */ -static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 110, 3); -} - -/** - * @brief Decode a gps_inject_data message into a struct - * - * @param msg The message to decode - * @param gps_inject_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_inject_data_decode(const mavlink_message_t* msg, mavlink_gps_inject_data_t* gps_inject_data) -{ -#if MAVLINK_NEED_BYTE_SWAP - gps_inject_data->target_system = mavlink_msg_gps_inject_data_get_target_system(msg); - gps_inject_data->target_component = mavlink_msg_gps_inject_data_get_target_component(msg); - gps_inject_data->len = mavlink_msg_gps_inject_data_get_len(msg); - mavlink_msg_gps_inject_data_get_data(msg, gps_inject_data->data); -#else - memcpy(gps_inject_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h deleted file mode 100644 index b53996206..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h +++ /dev/null @@ -1,425 +0,0 @@ -// MESSAGE GPS_RAW_INT PACKING - -#define MAVLINK_MSG_ID_GPS_RAW_INT 24 - -typedef struct __mavlink_gps_raw_int_t -{ - uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - int32_t lat; ///< Latitude (WGS84), in degrees * 1E7 - int32_t lon; ///< Longitude (WGS84), in degrees * 1E7 - int32_t alt; ///< Altitude (WGS84), in meters * 1000 (positive for up) - uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255 -} mavlink_gps_raw_int_t; - -#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30 -#define MAVLINK_MSG_ID_24_LEN 30 - -#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24 -#define MAVLINK_MSG_ID_24_CRC 24 - - - -#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \ - "GPS_RAW_INT", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \ - } \ -} - - -/** - * @brief Pack a gps_raw_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#else - mavlink_gps_raw_int_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif -} - -/** - * @brief Pack a gps_raw_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#else - mavlink_gps_raw_int_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif -} - -/** - * @brief Encode a gps_raw_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_raw_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) -{ - return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); -} - -/** - * @brief Encode a gps_raw_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_raw_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int) -{ - return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible); -} - -/** - * @brief Send a gps_raw_int message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - * @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif -#else - mavlink_gps_raw_int_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_uint16_t(buf, 26, cog); - _mav_put_uint8_t(buf, 28, fix_type); - _mav_put_uint8_t(buf, 29, satellites_visible); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif -#else - mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE GPS_RAW_INT UNPACKING - - -/** - * @brief Get field time_usec from gps_raw_int message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from gps_raw_int message - * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - */ -static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field lat from gps_raw_int message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from gps_raw_int message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from gps_raw_int message - * - * @return Altitude (WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from gps_raw_int message - * - * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field epv from gps_raw_int message - * - * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field vel from gps_raw_int message - * - * @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field cog from gps_raw_int message - * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - */ -static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field satellites_visible from gps_raw_int message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 29); -} - -/** - * @brief Decode a gps_raw_int message into a struct - * - * @param msg The message to decode - * @param gps_raw_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int) -{ -#if MAVLINK_NEED_BYTE_SWAP - gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg); - gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg); - gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg); - gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg); - gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg); - gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg); - gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg); - gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg); - gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg); - gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg); -#else - memcpy(gps_raw_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RAW_INT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h deleted file mode 100644 index 10659d0dd..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h +++ /dev/null @@ -1,325 +0,0 @@ -// MESSAGE GPS_STATUS PACKING - -#define MAVLINK_MSG_ID_GPS_STATUS 25 - -typedef struct __mavlink_gps_status_t -{ - uint8_t satellites_visible; ///< Number of satellites visible - uint8_t satellite_prn[20]; ///< Global satellite ID - uint8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization - uint8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite - uint8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg. - uint8_t satellite_snr[20]; ///< Signal to noise ratio of satellite -} mavlink_gps_status_t; - -#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101 -#define MAVLINK_MSG_ID_25_LEN 101 - -#define MAVLINK_MSG_ID_GPS_STATUS_CRC 23 -#define MAVLINK_MSG_ID_25_CRC 23 - -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20 -#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20 - -#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \ - "GPS_STATUS", \ - 6, \ - { { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \ - { "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \ - { "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \ - { "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \ - { "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \ - { "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \ - } \ -} - - -/** - * @brief Pack a gps_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; - _mav_put_uint8_t(buf, 0, satellites_visible); - _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); - _mav_put_uint8_t_array(buf, 21, satellite_used, 20); - _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); - _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); - _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif -} - -/** - * @brief Pack a gps_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; - _mav_put_uint8_t(buf, 0, satellites_visible); - _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); - _mav_put_uint8_t_array(buf, 21, satellite_used, 20); - _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); - _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); - _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_GPS_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif -} - -/** - * @brief Encode a gps_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param gps_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) -{ - return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -} - -/** - * @brief Encode a gps_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_gps_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status) -{ - return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr); -} - -/** - * @brief Send a gps_status message - * @param chan MAVLink channel to send the message - * - * @param satellites_visible Number of satellites visible - * @param satellite_prn Global satellite ID - * @param satellite_used 0: Satellite not used, 1: used for localization - * @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite - * @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg. - * @param satellite_snr Signal to noise ratio of satellite - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_GPS_STATUS_LEN]; - _mav_put_uint8_t(buf, 0, satellites_visible); - _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); - _mav_put_uint8_t_array(buf, 21, satellite_used, 20); - _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); - _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); - _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif -#else - mavlink_gps_status_t packet; - packet.satellites_visible = satellites_visible; - mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, satellites_visible); - _mav_put_uint8_t_array(buf, 1, satellite_prn, 20); - _mav_put_uint8_t_array(buf, 21, satellite_used, 20); - _mav_put_uint8_t_array(buf, 41, satellite_elevation, 20); - _mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20); - _mav_put_uint8_t_array(buf, 81, satellite_snr, 20); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif -#else - mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf; - packet->satellites_visible = satellites_visible; - mav_array_memcpy(packet->satellite_prn, satellite_prn, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_used, satellite_used, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_elevation, satellite_elevation, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20); - mav_array_memcpy(packet->satellite_snr, satellite_snr, sizeof(uint8_t)*20); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE GPS_STATUS UNPACKING - - -/** - * @brief Get field satellites_visible from gps_status message - * - * @return Number of satellites visible - */ -static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field satellite_prn from gps_status message - * - * @return Global satellite ID - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1); -} - -/** - * @brief Get field satellite_used from gps_status message - * - * @return 0: Satellite not used, 1: used for localization - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21); -} - -/** - * @brief Get field satellite_elevation from gps_status message - * - * @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41); -} - -/** - * @brief Get field satellite_azimuth from gps_status message - * - * @return Direction of satellite, 0: 0 deg, 255: 360 deg. - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61); -} - -/** - * @brief Get field satellite_snr from gps_status message - * - * @return Signal to noise ratio of satellite - */ -static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr) -{ - return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81); -} - -/** - * @brief Decode a gps_status message into a struct - * - * @param msg The message to decode - * @param gps_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg); - mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn); - mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used); - mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation); - mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth); - mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr); -#else - memcpy(gps_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h deleted file mode 100644 index 902e381ca..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h +++ /dev/null @@ -1,326 +0,0 @@ -// MESSAGE HEARTBEAT PACKING - -#define MAVLINK_MSG_ID_HEARTBEAT 0 - -typedef struct __mavlink_heartbeat_t -{ - uint32_t custom_mode; ///< A bitfield for use for autopilot-specific flags. - uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - uint8_t autopilot; ///< Autopilot type / class. defined in MAV_AUTOPILOT ENUM - uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - uint8_t system_status; ///< System status flag, see MAV_STATE ENUM - uint8_t mavlink_version; ///< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version -} mavlink_heartbeat_t; - -#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9 -#define MAVLINK_MSG_ID_0_LEN 9 - -#define MAVLINK_MSG_ID_HEARTBEAT_CRC 50 -#define MAVLINK_MSG_ID_0_CRC 50 - - - -#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \ - "HEARTBEAT", \ - 6, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \ - { "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \ - { "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \ - { "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \ - } \ -} - - -/** - * @brief Pack a heartbeat message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif -} - -/** - * @brief Pack a heartbeat message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HEARTBEAT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif -} - -/** - * @brief Encode a heartbeat struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) -{ - return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -} - -/** - * @brief Encode a heartbeat struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat) -{ - return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status); -} - -/** - * @brief Send a heartbeat message - * @param chan MAVLink channel to send the message - * - * @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - * @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM - * @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - * @param custom_mode A bitfield for use for autopilot-specific flags. - * @param system_status System status flag, see MAV_STATE ENUM - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HEARTBEAT_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif -#else - mavlink_heartbeat_t packet; - packet.custom_mode = custom_mode; - packet.type = type; - packet.autopilot = autopilot; - packet.base_mode = base_mode; - packet.system_status = system_status; - packet.mavlink_version = 3; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 5, autopilot); - _mav_put_uint8_t(buf, 6, base_mode); - _mav_put_uint8_t(buf, 7, system_status); - _mav_put_uint8_t(buf, 8, 3); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif -#else - mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf; - packet->custom_mode = custom_mode; - packet->type = type; - packet->autopilot = autopilot; - packet->base_mode = base_mode; - packet->system_status = system_status; - packet->mavlink_version = 3; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HEARTBEAT UNPACKING - - -/** - * @brief Get field type from heartbeat message - * - * @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) - */ -static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field autopilot from heartbeat message - * - * @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM - */ -static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field base_mode from heartbeat message - * - * @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h - */ -static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field custom_mode from heartbeat message - * - * @return A bitfield for use for autopilot-specific flags. - */ -static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field system_status from heartbeat message - * - * @return System status flag, see MAV_STATE ENUM - */ -static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field mavlink_version from heartbeat message - * - * @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version - */ -static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Decode a heartbeat message into a struct - * - * @param msg The message to decode - * @param heartbeat C-struct to decode the message contents into - */ -static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat) -{ -#if MAVLINK_NEED_BYTE_SWAP - heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg); - heartbeat->type = mavlink_msg_heartbeat_get_type(msg); - heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg); - heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg); - heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg); - heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg); -#else - memcpy(heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HEARTBEAT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h deleted file mode 100644 index 2749cb097..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_highres_imu.h +++ /dev/null @@ -1,545 +0,0 @@ -// MESSAGE HIGHRES_IMU PACKING - -#define MAVLINK_MSG_ID_HIGHRES_IMU 105 - -typedef struct __mavlink_highres_imu_t -{ - uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot) - float xacc; ///< X acceleration (m/s^2) - float yacc; ///< Y acceleration (m/s^2) - float zacc; ///< Z acceleration (m/s^2) - float xgyro; ///< Angular speed around X axis (rad / sec) - float ygyro; ///< Angular speed around Y axis (rad / sec) - float zgyro; ///< Angular speed around Z axis (rad / sec) - float xmag; ///< X Magnetic field (Gauss) - float ymag; ///< Y Magnetic field (Gauss) - float zmag; ///< Z Magnetic field (Gauss) - float abs_pressure; ///< Absolute pressure in millibar - float diff_pressure; ///< Differential pressure in millibar - float pressure_alt; ///< Altitude calculated from pressure - float temperature; ///< Temperature in degrees celsius - uint16_t fields_updated; ///< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature -} mavlink_highres_imu_t; - -#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62 -#define MAVLINK_MSG_ID_105_LEN 62 - -#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93 -#define MAVLINK_MSG_ID_105_CRC 93 - - - -#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \ - "HIGHRES_IMU", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \ - } \ -} - - -/** - * @brief Pack a highres_imu message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif -} - -/** - * @brief Pack a highres_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint16_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif -} - -/** - * @brief Encode a highres_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param highres_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) -{ - return mavlink_msg_highres_imu_pack(system_id, component_id, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); -} - -/** - * @brief Encode a highres_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param highres_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu) -{ - return mavlink_msg_highres_imu_pack_chan(system_id, component_id, chan, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated); -} - -/** - * @brief Send a highres_imu message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis (rad / sec) - * @param ygyro Angular speed around Y axis (rad / sec) - * @param zgyro Angular speed around Z axis (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif -#else - mavlink_highres_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HIGHRES_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint16_t(buf, 60, fields_updated); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif -#else - mavlink_highres_imu_t *packet = (mavlink_highres_imu_t *)msgbuf; - packet->time_usec = time_usec; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - packet->abs_pressure = abs_pressure; - packet->diff_pressure = diff_pressure; - packet->pressure_alt = pressure_alt; - packet->temperature = temperature; - packet->fields_updated = fields_updated; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HIGHRES_IMU UNPACKING - - -/** - * @brief Get field time_usec from highres_imu message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from highres_imu message - * - * @return X acceleration (m/s^2) - */ -static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yacc from highres_imu message - * - * @return Y acceleration (m/s^2) - */ -static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field zacc from highres_imu message - * - * @return Z acceleration (m/s^2) - */ -static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field xgyro from highres_imu message - * - * @return Angular speed around X axis (rad / sec) - */ -static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field ygyro from highres_imu message - * - * @return Angular speed around Y axis (rad / sec) - */ -static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field zgyro from highres_imu message - * - * @return Angular speed around Z axis (rad / sec) - */ -static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field xmag from highres_imu message - * - * @return X Magnetic field (Gauss) - */ -static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ymag from highres_imu message - * - * @return Y Magnetic field (Gauss) - */ -static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field zmag from highres_imu message - * - * @return Z Magnetic field (Gauss) - */ -static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field abs_pressure from highres_imu message - * - * @return Absolute pressure in millibar - */ -static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field diff_pressure from highres_imu message - * - * @return Differential pressure in millibar - */ -static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field pressure_alt from highres_imu message - * - * @return Altitude calculated from pressure - */ -static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field temperature from highres_imu message - * - * @return Temperature in degrees celsius - */ -static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field fields_updated from highres_imu message - * - * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - */ -static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 60); -} - -/** - * @brief Decode a highres_imu message into a struct - * - * @param msg The message to decode - * @param highres_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* msg, mavlink_highres_imu_t* highres_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP - highres_imu->time_usec = mavlink_msg_highres_imu_get_time_usec(msg); - highres_imu->xacc = mavlink_msg_highres_imu_get_xacc(msg); - highres_imu->yacc = mavlink_msg_highres_imu_get_yacc(msg); - highres_imu->zacc = mavlink_msg_highres_imu_get_zacc(msg); - highres_imu->xgyro = mavlink_msg_highres_imu_get_xgyro(msg); - highres_imu->ygyro = mavlink_msg_highres_imu_get_ygyro(msg); - highres_imu->zgyro = mavlink_msg_highres_imu_get_zgyro(msg); - highres_imu->xmag = mavlink_msg_highres_imu_get_xmag(msg); - highres_imu->ymag = mavlink_msg_highres_imu_get_ymag(msg); - highres_imu->zmag = mavlink_msg_highres_imu_get_zmag(msg); - highres_imu->abs_pressure = mavlink_msg_highres_imu_get_abs_pressure(msg); - highres_imu->diff_pressure = mavlink_msg_highres_imu_get_diff_pressure(msg); - highres_imu->pressure_alt = mavlink_msg_highres_imu_get_pressure_alt(msg); - highres_imu->temperature = mavlink_msg_highres_imu_get_temperature(msg); - highres_imu->fields_updated = mavlink_msg_highres_imu_get_fields_updated(msg); -#else - memcpy(highres_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIGHRES_IMU_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h deleted file mode 100644 index f7507b1cf..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h +++ /dev/null @@ -1,449 +0,0 @@ -// MESSAGE HIL_CONTROLS PACKING - -#define MAVLINK_MSG_ID_HIL_CONTROLS 91 - -typedef struct __mavlink_hil_controls_t -{ - uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - float roll_ailerons; ///< Control output -1 .. 1 - float pitch_elevator; ///< Control output -1 .. 1 - float yaw_rudder; ///< Control output -1 .. 1 - float throttle; ///< Throttle 0 .. 1 - float aux1; ///< Aux 1, -1 .. 1 - float aux2; ///< Aux 2, -1 .. 1 - float aux3; ///< Aux 3, -1 .. 1 - float aux4; ///< Aux 4, -1 .. 1 - uint8_t mode; ///< System mode (MAV_MODE) - uint8_t nav_mode; ///< Navigation mode (MAV_NAV_MODE) -} mavlink_hil_controls_t; - -#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42 -#define MAVLINK_MSG_ID_91_LEN 42 - -#define MAVLINK_MSG_ID_HIL_CONTROLS_CRC 63 -#define MAVLINK_MSG_ID_91_CRC 63 - - - -#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \ - "HIL_CONTROLS", \ - 11, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \ - { "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \ - { "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \ - { "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \ - { "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \ - { "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \ - { "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \ - { "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \ - { "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \ - { "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \ - } \ -} - - -/** - * @brief Pack a hil_controls message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif -} - -/** - * @brief Pack a hil_controls message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif -} - -/** - * @brief Encode a hil_controls struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) -{ - return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -} - -/** - * @brief Encode a hil_controls struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_controls C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_controls_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls) -{ - return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode); -} - -/** - * @brief Send a hil_controls message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll_ailerons Control output -1 .. 1 - * @param pitch_elevator Control output -1 .. 1 - * @param yaw_rudder Control output -1 .. 1 - * @param throttle Throttle 0 .. 1 - * @param aux1 Aux 1, -1 .. 1 - * @param aux2 Aux 2, -1 .. 1 - * @param aux3 Aux 3, -1 .. 1 - * @param aux4 Aux 4, -1 .. 1 - * @param mode System mode (MAV_MODE) - * @param nav_mode Navigation mode (MAV_NAV_MODE) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_CONTROLS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif -#else - mavlink_hil_controls_t packet; - packet.time_usec = time_usec; - packet.roll_ailerons = roll_ailerons; - packet.pitch_elevator = pitch_elevator; - packet.yaw_rudder = yaw_rudder; - packet.throttle = throttle; - packet.aux1 = aux1; - packet.aux2 = aux2; - packet.aux3 = aux3; - packet.aux4 = aux4; - packet.mode = mode; - packet.nav_mode = nav_mode; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll_ailerons); - _mav_put_float(buf, 12, pitch_elevator); - _mav_put_float(buf, 16, yaw_rudder); - _mav_put_float(buf, 20, throttle); - _mav_put_float(buf, 24, aux1); - _mav_put_float(buf, 28, aux2); - _mav_put_float(buf, 32, aux3); - _mav_put_float(buf, 36, aux4); - _mav_put_uint8_t(buf, 40, mode); - _mav_put_uint8_t(buf, 41, nav_mode); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif -#else - mavlink_hil_controls_t *packet = (mavlink_hil_controls_t *)msgbuf; - packet->time_usec = time_usec; - packet->roll_ailerons = roll_ailerons; - packet->pitch_elevator = pitch_elevator; - packet->yaw_rudder = yaw_rudder; - packet->throttle = throttle; - packet->aux1 = aux1; - packet->aux2 = aux2; - packet->aux3 = aux3; - packet->aux4 = aux4; - packet->mode = mode; - packet->nav_mode = nav_mode; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HIL_CONTROLS UNPACKING - - -/** - * @brief Get field time_usec from hil_controls message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field roll_ailerons from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch_elevator from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw_rudder from hil_controls message - * - * @return Control output -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field throttle from hil_controls message - * - * @return Throttle 0 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field aux1 from hil_controls message - * - * @return Aux 1, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field aux2 from hil_controls message - * - * @return Aux 2, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field aux3 from hil_controls message - * - * @return Aux 3, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field aux4 from hil_controls message - * - * @return Aux 4, -1 .. 1 - */ -static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field mode from hil_controls message - * - * @return System mode (MAV_MODE) - */ -static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field nav_mode from hil_controls message - * - * @return Navigation mode (MAV_NAV_MODE) - */ -static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Decode a hil_controls message into a struct - * - * @param msg The message to decode - * @param hil_controls C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls) -{ -#if MAVLINK_NEED_BYTE_SWAP - hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg); - hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg); - hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg); - hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg); - hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg); - hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg); - hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg); - hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg); - hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg); - hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg); - hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg); -#else - memcpy(hil_controls, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_CONTROLS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h deleted file mode 100644 index a22c0472f..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_gps.h +++ /dev/null @@ -1,497 +0,0 @@ -// MESSAGE HIL_GPS PACKING - -#define MAVLINK_MSG_ID_HIL_GPS 113 - -typedef struct __mavlink_hil_gps_t -{ - uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - int32_t lat; ///< Latitude (WGS84), in degrees * 1E7 - int32_t lon; ///< Longitude (WGS84), in degrees * 1E7 - int32_t alt; ///< Altitude (WGS84), in meters * 1000 (positive for up) - uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535 - int16_t vn; ///< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - int16_t ve; ///< GPS velocity in cm/s in EAST direction in earth-fixed NED frame - int16_t vd; ///< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255 -} mavlink_hil_gps_t; - -#define MAVLINK_MSG_ID_HIL_GPS_LEN 36 -#define MAVLINK_MSG_ID_113_LEN 36 - -#define MAVLINK_MSG_ID_HIL_GPS_CRC 124 -#define MAVLINK_MSG_ID_113_CRC 124 - - - -#define MAVLINK_MESSAGE_INFO_HIL_GPS { \ - "HIL_GPS", \ - 13, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \ - { "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \ - { "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \ - { "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \ - { "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \ - { "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \ - { "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \ - { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \ - } \ -} - - -/** - * @brief Pack a hil_gps message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_GPS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif -} - -/** - * @brief Pack a hil_gps message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_GPS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif -} - -/** - * @brief Encode a hil_gps struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_gps C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) -{ - return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); -} - -/** - * @brief Encode a hil_gps struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_gps C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps) -{ - return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible); -} - -/** - * @brief Send a hil_gps message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - * @param lat Latitude (WGS84), in degrees * 1E7 - * @param lon Longitude (WGS84), in degrees * 1E7 - * @param alt Altitude (WGS84), in meters * 1000 (positive for up) - * @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - * @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - * @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535 - * @param vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - * @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame - * @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - * @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - * @param satellites_visible Number of satellites visible. If unknown, set to 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_gps_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_GPS_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif -#else - mavlink_hil_gps_t packet; - packet.time_usec = time_usec; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.eph = eph; - packet.epv = epv; - packet.vel = vel; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - packet.cog = cog; - packet.fix_type = fix_type; - packet.satellites_visible = satellites_visible; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int32_t(buf, 8, lat); - _mav_put_int32_t(buf, 12, lon); - _mav_put_int32_t(buf, 16, alt); - _mav_put_uint16_t(buf, 20, eph); - _mav_put_uint16_t(buf, 22, epv); - _mav_put_uint16_t(buf, 24, vel); - _mav_put_int16_t(buf, 26, vn); - _mav_put_int16_t(buf, 28, ve); - _mav_put_int16_t(buf, 30, vd); - _mav_put_uint16_t(buf, 32, cog); - _mav_put_uint8_t(buf, 34, fix_type); - _mav_put_uint8_t(buf, 35, satellites_visible); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif -#else - mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf; - packet->time_usec = time_usec; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->eph = eph; - packet->epv = epv; - packet->vel = vel; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - packet->cog = cog; - packet->fix_type = fix_type; - packet->satellites_visible = satellites_visible; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HIL_GPS UNPACKING - - -/** - * @brief Get field time_usec from hil_gps message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field fix_type from hil_gps message - * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. - */ -static inline uint8_t mavlink_msg_hil_gps_get_fix_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field lat from hil_gps message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field lon from hil_gps message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt from hil_gps message - * - * @return Altitude (WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field eph from hil_gps message - * - * @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field epv from hil_gps message - * - * @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field vel from hil_gps message - * - * @return GPS ground speed (m/s * 100). If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field vn from hil_gps message - * - * @return GPS velocity in cm/s in NORTH direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 26); -} - -/** - * @brief Get field ve from hil_gps message - * - * @return GPS velocity in cm/s in EAST direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 28); -} - -/** - * @brief Get field vd from hil_gps message - * - * @return GPS velocity in cm/s in DOWN direction in earth-fixed NED frame - */ -static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 30); -} - -/** - * @brief Get field cog from hil_gps message - * - * @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 - */ -static inline uint16_t mavlink_msg_hil_gps_get_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field satellites_visible from hil_gps message - * - * @return Number of satellites visible. If unknown, set to 255 - */ -static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Decode a hil_gps message into a struct - * - * @param msg The message to decode - * @param hil_gps C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps) -{ -#if MAVLINK_NEED_BYTE_SWAP - hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg); - hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg); - hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg); - hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg); - hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg); - hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg); - hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg); - hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg); - hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg); - hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg); - hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg); - hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg); - hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg); -#else - memcpy(hil_gps, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_GPS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h deleted file mode 100644 index eaadf2435..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_optical_flow.h +++ /dev/null @@ -1,377 +0,0 @@ -// MESSAGE HIL_OPTICAL_FLOW PACKING - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114 - -typedef struct __mavlink_hil_optical_flow_t -{ - uint64_t time_usec; ///< Timestamp (UNIX) - float flow_comp_m_x; ///< Flow in meters in x-sensor direction, angular-speed compensated - float flow_comp_m_y; ///< Flow in meters in y-sensor direction, angular-speed compensated - float ground_distance; ///< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - int16_t flow_x; ///< Flow in pixels in x-sensor direction - int16_t flow_y; ///< Flow in pixels in y-sensor direction - uint8_t sensor_id; ///< Sensor ID - uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality -} mavlink_hil_optical_flow_t; - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 26 -#define MAVLINK_MSG_ID_114_LEN 26 - -#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 119 -#define MAVLINK_MSG_ID_114_CRC 119 - - - -#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \ - "HIL_OPTICAL_FLOW", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, flow_comp_m_y) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, ground_distance) }, \ - { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_hil_optical_flow_t, flow_x) }, \ - { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_hil_optical_flow_t, flow_y) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_hil_optical_flow_t, quality) }, \ - } \ -} - - -/** - * @brief Pack a hil_optical_flow message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels in x-sensor direction - * @param flow_y Flow in pixels in y-sensor direction - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif -} - -/** - * @brief Pack a hil_optical_flow message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels in x-sensor direction - * @param flow_y Flow in pixels in y-sensor direction - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif -} - -/** - * @brief Encode a hil_optical_flow struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ - return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->flow_x, hil_optical_flow->flow_y, hil_optical_flow->flow_comp_m_x, hil_optical_flow->flow_comp_m_y, hil_optical_flow->quality, hil_optical_flow->ground_distance); -} - -/** - * @brief Encode a hil_optical_flow struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow) -{ - return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->flow_x, hil_optical_flow->flow_y, hil_optical_flow->flow_comp_m_x, hil_optical_flow->flow_comp_m_y, hil_optical_flow->quality, hil_optical_flow->ground_distance); -} - -/** - * @brief Send a hil_optical_flow message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels in x-sensor direction - * @param flow_y Flow in pixels in y-sensor direction - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif -#else - mavlink_hil_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif -#else - mavlink_hil_optical_flow_t *packet = (mavlink_hil_optical_flow_t *)msgbuf; - packet->time_usec = time_usec; - packet->flow_comp_m_x = flow_comp_m_x; - packet->flow_comp_m_y = flow_comp_m_y; - packet->ground_distance = ground_distance; - packet->flow_x = flow_x; - packet->flow_y = flow_y; - packet->sensor_id = sensor_id; - packet->quality = quality; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HIL_OPTICAL_FLOW UNPACKING - - -/** - * @brief Get field time_usec from hil_optical_flow message - * - * @return Timestamp (UNIX) - */ -static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from hil_optical_flow message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field flow_x from hil_optical_flow message - * - * @return Flow in pixels in x-sensor direction - */ -static inline int16_t mavlink_msg_hil_optical_flow_get_flow_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field flow_y from hil_optical_flow message - * - * @return Flow in pixels in y-sensor direction - */ -static inline int16_t mavlink_msg_hil_optical_flow_get_flow_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field flow_comp_m_x from hil_optical_flow message - * - * @return Flow in meters in x-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_hil_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field flow_comp_m_y from hil_optical_flow message - * - * @return Flow in meters in y-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_hil_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field quality from hil_optical_flow message - * - * @return Optical flow quality / confidence. 0: bad, 255: maximum quality - */ -static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field ground_distance from hil_optical_flow message - * - * @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - */ -static inline float mavlink_msg_hil_optical_flow_get_ground_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a hil_optical_flow message into a struct - * - * @param msg The message to decode - * @param hil_optical_flow C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t* msg, mavlink_hil_optical_flow_t* hil_optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP - hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg); - hil_optical_flow->flow_comp_m_x = mavlink_msg_hil_optical_flow_get_flow_comp_m_x(msg); - hil_optical_flow->flow_comp_m_y = mavlink_msg_hil_optical_flow_get_flow_comp_m_y(msg); - hil_optical_flow->ground_distance = mavlink_msg_hil_optical_flow_get_ground_distance(msg); - hil_optical_flow->flow_x = mavlink_msg_hil_optical_flow_get_flow_x(msg); - hil_optical_flow->flow_y = mavlink_msg_hil_optical_flow_get_flow_y(msg); - hil_optical_flow->sensor_id = mavlink_msg_hil_optical_flow_get_sensor_id(msg); - hil_optical_flow->quality = mavlink_msg_hil_optical_flow_get_quality(msg); -#else - memcpy(hil_optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h deleted file mode 100644 index 227cd9d94..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h +++ /dev/null @@ -1,521 +0,0 @@ -// MESSAGE HIL_RC_INPUTS_RAW PACKING - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92 - -typedef struct __mavlink_hil_rc_inputs_raw_t -{ - uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - uint16_t chan1_raw; ///< RC channel 1 value, in microseconds - uint16_t chan2_raw; ///< RC channel 2 value, in microseconds - uint16_t chan3_raw; ///< RC channel 3 value, in microseconds - uint16_t chan4_raw; ///< RC channel 4 value, in microseconds - uint16_t chan5_raw; ///< RC channel 5 value, in microseconds - uint16_t chan6_raw; ///< RC channel 6 value, in microseconds - uint16_t chan7_raw; ///< RC channel 7 value, in microseconds - uint16_t chan8_raw; ///< RC channel 8 value, in microseconds - uint16_t chan9_raw; ///< RC channel 9 value, in microseconds - uint16_t chan10_raw; ///< RC channel 10 value, in microseconds - uint16_t chan11_raw; ///< RC channel 11 value, in microseconds - uint16_t chan12_raw; ///< RC channel 12 value, in microseconds - uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100% -} mavlink_hil_rc_inputs_raw_t; - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33 -#define MAVLINK_MSG_ID_92_LEN 33 - -#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54 -#define MAVLINK_MSG_ID_92_CRC 54 - - - -#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \ - "HIL_RC_INPUTS_RAW", \ - 14, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \ - } \ -} - - -/** - * @brief Pack a hil_rc_inputs_raw message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#else - mavlink_hil_rc_inputs_raw_t packet; - packet.time_usec = time_usec; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif -} - -/** - * @brief Pack a hil_rc_inputs_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#else - mavlink_hil_rc_inputs_raw_t packet; - packet.time_usec = time_usec; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif -} - -/** - * @brief Encode a hil_rc_inputs_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_rc_inputs_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ - return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -} - -/** - * @brief Encode a hil_rc_inputs_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_rc_inputs_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ - return mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, chan, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi); -} - -/** - * @brief Send a hil_rc_inputs_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param chan1_raw RC channel 1 value, in microseconds - * @param chan2_raw RC channel 2 value, in microseconds - * @param chan3_raw RC channel 3 value, in microseconds - * @param chan4_raw RC channel 4 value, in microseconds - * @param chan5_raw RC channel 5 value, in microseconds - * @param chan6_raw RC channel 6 value, in microseconds - * @param chan7_raw RC channel 7 value, in microseconds - * @param chan8_raw RC channel 8 value, in microseconds - * @param chan9_raw RC channel 9 value, in microseconds - * @param chan10_raw RC channel 10 value, in microseconds - * @param chan11_raw RC channel 11 value, in microseconds - * @param chan12_raw RC channel 12 value, in microseconds - * @param rssi Receive signal strength indicator, 0: 0%, 255: 100% - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif -#else - mavlink_hil_rc_inputs_raw_t packet; - packet.time_usec = time_usec; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.rssi = rssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 8, chan1_raw); - _mav_put_uint16_t(buf, 10, chan2_raw); - _mav_put_uint16_t(buf, 12, chan3_raw); - _mav_put_uint16_t(buf, 14, chan4_raw); - _mav_put_uint16_t(buf, 16, chan5_raw); - _mav_put_uint16_t(buf, 18, chan6_raw); - _mav_put_uint16_t(buf, 20, chan7_raw); - _mav_put_uint16_t(buf, 22, chan8_raw); - _mav_put_uint16_t(buf, 24, chan9_raw); - _mav_put_uint16_t(buf, 26, chan10_raw); - _mav_put_uint16_t(buf, 28, chan11_raw); - _mav_put_uint16_t(buf, 30, chan12_raw); - _mav_put_uint8_t(buf, 32, rssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif -#else - mavlink_hil_rc_inputs_raw_t *packet = (mavlink_hil_rc_inputs_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->chan9_raw = chan9_raw; - packet->chan10_raw = chan10_raw; - packet->chan11_raw = chan11_raw; - packet->chan12_raw = chan12_raw; - packet->rssi = rssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HIL_RC_INPUTS_RAW UNPACKING - - -/** - * @brief Get field time_usec from hil_rc_inputs_raw message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field chan1_raw from hil_rc_inputs_raw message - * - * @return RC channel 1 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan2_raw from hil_rc_inputs_raw message - * - * @return RC channel 2 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan3_raw from hil_rc_inputs_raw message - * - * @return RC channel 3 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan4_raw from hil_rc_inputs_raw message - * - * @return RC channel 4 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan5_raw from hil_rc_inputs_raw message - * - * @return RC channel 5 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan6_raw from hil_rc_inputs_raw message - * - * @return RC channel 6 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field chan7_raw from hil_rc_inputs_raw message - * - * @return RC channel 7 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field chan8_raw from hil_rc_inputs_raw message - * - * @return RC channel 8 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field chan9_raw from hil_rc_inputs_raw message - * - * @return RC channel 9 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field chan10_raw from hil_rc_inputs_raw message - * - * @return RC channel 10 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field chan11_raw from hil_rc_inputs_raw message - * - * @return RC channel 11 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field chan12_raw from hil_rc_inputs_raw message - * - * @return RC channel 12 value, in microseconds - */ -static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field rssi from hil_rc_inputs_raw message - * - * @return Receive signal strength indicator, 0: 0%, 255: 100% - */ -static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Decode a hil_rc_inputs_raw message into a struct - * - * @param msg The message to decode - * @param hil_rc_inputs_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* msg, mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP - hil_rc_inputs_raw->time_usec = mavlink_msg_hil_rc_inputs_raw_get_time_usec(msg); - hil_rc_inputs_raw->chan1_raw = mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(msg); - hil_rc_inputs_raw->chan2_raw = mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(msg); - hil_rc_inputs_raw->chan3_raw = mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(msg); - hil_rc_inputs_raw->chan4_raw = mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(msg); - hil_rc_inputs_raw->chan5_raw = mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(msg); - hil_rc_inputs_raw->chan6_raw = mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(msg); - hil_rc_inputs_raw->chan7_raw = mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(msg); - hil_rc_inputs_raw->chan8_raw = mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(msg); - hil_rc_inputs_raw->chan9_raw = mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(msg); - hil_rc_inputs_raw->chan10_raw = mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(msg); - hil_rc_inputs_raw->chan11_raw = mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(msg); - hil_rc_inputs_raw->chan12_raw = mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(msg); - hil_rc_inputs_raw->rssi = mavlink_msg_hil_rc_inputs_raw_get_rssi(msg); -#else - memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h deleted file mode 100644 index 8672f8b8a..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_sensor.h +++ /dev/null @@ -1,545 +0,0 @@ -// MESSAGE HIL_SENSOR PACKING - -#define MAVLINK_MSG_ID_HIL_SENSOR 107 - -typedef struct __mavlink_hil_sensor_t -{ - uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot) - float xacc; ///< X acceleration (m/s^2) - float yacc; ///< Y acceleration (m/s^2) - float zacc; ///< Z acceleration (m/s^2) - float xgyro; ///< Angular speed around X axis in body frame (rad / sec) - float ygyro; ///< Angular speed around Y axis in body frame (rad / sec) - float zgyro; ///< Angular speed around Z axis in body frame (rad / sec) - float xmag; ///< X Magnetic field (Gauss) - float ymag; ///< Y Magnetic field (Gauss) - float zmag; ///< Z Magnetic field (Gauss) - float abs_pressure; ///< Absolute pressure in millibar - float diff_pressure; ///< Differential pressure (airspeed) in millibar - float pressure_alt; ///< Altitude calculated from pressure - float temperature; ///< Temperature in degrees celsius - uint32_t fields_updated; ///< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature -} mavlink_hil_sensor_t; - -#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64 -#define MAVLINK_MSG_ID_107_LEN 64 - -#define MAVLINK_MSG_ID_HIL_SENSOR_CRC 108 -#define MAVLINK_MSG_ID_107_CRC 108 - - - -#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \ - "HIL_SENSOR", \ - 15, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \ - { "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \ - { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \ - { "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \ - { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \ - { "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \ - } \ -} - - -/** - * @brief Pack a hil_sensor message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#else - mavlink_hil_sensor_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif -} - -/** - * @brief Pack a hil_sensor message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint32_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#else - mavlink_hil_sensor_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif -} - -/** - * @brief Encode a hil_sensor struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) -{ - return mavlink_msg_hil_sensor_pack(system_id, component_id, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated); -} - -/** - * @brief Encode a hil_sensor struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_sensor C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor) -{ - return mavlink_msg_hil_sensor_pack_chan(system_id, component_id, chan, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated); -} - -/** - * @brief Send a hil_sensor message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param xacc X acceleration (m/s^2) - * @param yacc Y acceleration (m/s^2) - * @param zacc Z acceleration (m/s^2) - * @param xgyro Angular speed around X axis in body frame (rad / sec) - * @param ygyro Angular speed around Y axis in body frame (rad / sec) - * @param zgyro Angular speed around Z axis in body frame (rad / sec) - * @param xmag X Magnetic field (Gauss) - * @param ymag Y Magnetic field (Gauss) - * @param zmag Z Magnetic field (Gauss) - * @param abs_pressure Absolute pressure in millibar - * @param diff_pressure Differential pressure (airspeed) in millibar - * @param pressure_alt Altitude calculated from pressure - * @param temperature Temperature in degrees celsius - * @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif -#else - mavlink_hil_sensor_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - packet.abs_pressure = abs_pressure; - packet.diff_pressure = diff_pressure; - packet.pressure_alt = pressure_alt; - packet.temperature = temperature; - packet.fields_updated = fields_updated; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HIL_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, xacc); - _mav_put_float(buf, 12, yacc); - _mav_put_float(buf, 16, zacc); - _mav_put_float(buf, 20, xgyro); - _mav_put_float(buf, 24, ygyro); - _mav_put_float(buf, 28, zgyro); - _mav_put_float(buf, 32, xmag); - _mav_put_float(buf, 36, ymag); - _mav_put_float(buf, 40, zmag); - _mav_put_float(buf, 44, abs_pressure); - _mav_put_float(buf, 48, diff_pressure); - _mav_put_float(buf, 52, pressure_alt); - _mav_put_float(buf, 56, temperature); - _mav_put_uint32_t(buf, 60, fields_updated); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif -#else - mavlink_hil_sensor_t *packet = (mavlink_hil_sensor_t *)msgbuf; - packet->time_usec = time_usec; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - packet->abs_pressure = abs_pressure; - packet->diff_pressure = diff_pressure; - packet->pressure_alt = pressure_alt; - packet->temperature = temperature; - packet->fields_updated = fields_updated; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HIL_SENSOR UNPACKING - - -/** - * @brief Get field time_usec from hil_sensor message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from hil_sensor message - * - * @return X acceleration (m/s^2) - */ -static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yacc from hil_sensor message - * - * @return Y acceleration (m/s^2) - */ -static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field zacc from hil_sensor message - * - * @return Z acceleration (m/s^2) - */ -static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field xgyro from hil_sensor message - * - * @return Angular speed around X axis in body frame (rad / sec) - */ -static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field ygyro from hil_sensor message - * - * @return Angular speed around Y axis in body frame (rad / sec) - */ -static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field zgyro from hil_sensor message - * - * @return Angular speed around Z axis in body frame (rad / sec) - */ -static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field xmag from hil_sensor message - * - * @return X Magnetic field (Gauss) - */ -static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field ymag from hil_sensor message - * - * @return Y Magnetic field (Gauss) - */ -static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field zmag from hil_sensor message - * - * @return Z Magnetic field (Gauss) - */ -static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field abs_pressure from hil_sensor message - * - * @return Absolute pressure in millibar - */ -static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field diff_pressure from hil_sensor message - * - * @return Differential pressure (airspeed) in millibar - */ -static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field pressure_alt from hil_sensor message - * - * @return Altitude calculated from pressure - */ -static inline float mavlink_msg_hil_sensor_get_pressure_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field temperature from hil_sensor message - * - * @return Temperature in degrees celsius - */ -static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field fields_updated from hil_sensor message - * - * @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature - */ -static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 60); -} - -/** - * @brief Decode a hil_sensor message into a struct - * - * @param msg The message to decode - * @param hil_sensor C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_sensor_decode(const mavlink_message_t* msg, mavlink_hil_sensor_t* hil_sensor) -{ -#if MAVLINK_NEED_BYTE_SWAP - hil_sensor->time_usec = mavlink_msg_hil_sensor_get_time_usec(msg); - hil_sensor->xacc = mavlink_msg_hil_sensor_get_xacc(msg); - hil_sensor->yacc = mavlink_msg_hil_sensor_get_yacc(msg); - hil_sensor->zacc = mavlink_msg_hil_sensor_get_zacc(msg); - hil_sensor->xgyro = mavlink_msg_hil_sensor_get_xgyro(msg); - hil_sensor->ygyro = mavlink_msg_hil_sensor_get_ygyro(msg); - hil_sensor->zgyro = mavlink_msg_hil_sensor_get_zgyro(msg); - hil_sensor->xmag = mavlink_msg_hil_sensor_get_xmag(msg); - hil_sensor->ymag = mavlink_msg_hil_sensor_get_ymag(msg); - hil_sensor->zmag = mavlink_msg_hil_sensor_get_zmag(msg); - hil_sensor->abs_pressure = mavlink_msg_hil_sensor_get_abs_pressure(msg); - hil_sensor->diff_pressure = mavlink_msg_hil_sensor_get_diff_pressure(msg); - hil_sensor->pressure_alt = mavlink_msg_hil_sensor_get_pressure_alt(msg); - hil_sensor->temperature = mavlink_msg_hil_sensor_get_temperature(msg); - hil_sensor->fields_updated = mavlink_msg_hil_sensor_get_fields_updated(msg); -#else - memcpy(hil_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_SENSOR_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h deleted file mode 100644 index 923ed60b9..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h +++ /dev/null @@ -1,569 +0,0 @@ -// MESSAGE HIL_STATE PACKING - -#define MAVLINK_MSG_ID_HIL_STATE 90 - -typedef struct __mavlink_hil_state_t -{ - uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - float roll; ///< Roll angle (rad) - float pitch; ///< Pitch angle (rad) - float yaw; ///< Yaw angle (rad) - float rollspeed; ///< Body frame roll / phi angular speed (rad/s) - float pitchspeed; ///< Body frame pitch / theta angular speed (rad/s) - float yawspeed; ///< Body frame yaw / psi angular speed (rad/s) - int32_t lat; ///< Latitude, expressed as * 1E7 - int32_t lon; ///< Longitude, expressed as * 1E7 - int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters) - int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 - int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 - int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 - int16_t xacc; ///< X acceleration (mg) - int16_t yacc; ///< Y acceleration (mg) - int16_t zacc; ///< Z acceleration (mg) -} mavlink_hil_state_t; - -#define MAVLINK_MSG_ID_HIL_STATE_LEN 56 -#define MAVLINK_MSG_ID_90_LEN 56 - -#define MAVLINK_MSG_ID_HIL_STATE_CRC 183 -#define MAVLINK_MSG_ID_90_CRC 183 - - - -#define MAVLINK_MESSAGE_INFO_HIL_STATE { \ - "HIL_STATE", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \ - } \ -} - - -/** - * @brief Pack a hil_state message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll); - _mav_put_float(buf, 12, pitch); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif -} - -/** - * @brief Pack a hil_state message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll); - _mav_put_float(buf, 12, pitch); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif -} - -/** - * @brief Encode a hil_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) -{ - return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -} - -/** - * @brief Encode a hil_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state) -{ - return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc); -} - -/** - * @brief Send a hil_state message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param roll Roll angle (rad) - * @param pitch Pitch angle (rad) - * @param yaw Yaw angle (rad) - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll); - _mav_put_float(buf, 12, pitch); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif -#else - mavlink_hil_state_t packet; - packet.time_usec = time_usec; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, roll); - _mav_put_float(buf, 12, pitch); - _mav_put_float(buf, 16, yaw); - _mav_put_float(buf, 20, rollspeed); - _mav_put_float(buf, 24, pitchspeed); - _mav_put_float(buf, 28, yawspeed); - _mav_put_int32_t(buf, 32, lat); - _mav_put_int32_t(buf, 36, lon); - _mav_put_int32_t(buf, 40, alt); - _mav_put_int16_t(buf, 44, vx); - _mav_put_int16_t(buf, 46, vy); - _mav_put_int16_t(buf, 48, vz); - _mav_put_int16_t(buf, 50, xacc); - _mav_put_int16_t(buf, 52, yacc); - _mav_put_int16_t(buf, 54, zacc); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif -#else - mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf; - packet->time_usec = time_usec; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HIL_STATE UNPACKING - - -/** - * @brief Get field time_usec from hil_state message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field roll from hil_state message - * - * @return Roll angle (rad) - */ -static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field pitch from hil_state message - * - * @return Pitch angle (rad) - */ -static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yaw from hil_state message - * - * @return Yaw angle (rad) - */ -static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rollspeed from hil_state message - * - * @return Body frame roll / phi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitchspeed from hil_state message - * - * @return Body frame pitch / theta angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yawspeed from hil_state message - * - * @return Body frame yaw / psi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field lat from hil_state message - * - * @return Latitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 32); -} - -/** - * @brief Get field lon from hil_state message - * - * @return Longitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field alt from hil_state message - * - * @return Altitude in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 40); -} - -/** - * @brief Get field vx from hil_state message - * - * @return Ground X Speed (Latitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 44); -} - -/** - * @brief Get field vy from hil_state message - * - * @return Ground Y Speed (Longitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 46); -} - -/** - * @brief Get field vz from hil_state message - * - * @return Ground Z Speed (Altitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field xacc from hil_state message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field yacc from hil_state message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field zacc from hil_state message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 54); -} - -/** - * @brief Decode a hil_state message into a struct - * - * @param msg The message to decode - * @param hil_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state) -{ -#if MAVLINK_NEED_BYTE_SWAP - hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg); - hil_state->roll = mavlink_msg_hil_state_get_roll(msg); - hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg); - hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg); - hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg); - hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg); - hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg); - hil_state->lat = mavlink_msg_hil_state_get_lat(msg); - hil_state->lon = mavlink_msg_hil_state_get_lon(msg); - hil_state->alt = mavlink_msg_hil_state_get_alt(msg); - hil_state->vx = mavlink_msg_hil_state_get_vx(msg); - hil_state->vy = mavlink_msg_hil_state_get_vy(msg); - hil_state->vz = mavlink_msg_hil_state_get_vz(msg); - hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg); - hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg); - hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg); -#else - memcpy(hil_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h deleted file mode 100644 index 1a028bdf9..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_hil_state_quaternion.h +++ /dev/null @@ -1,561 +0,0 @@ -// MESSAGE HIL_STATE_QUATERNION PACKING - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115 - -typedef struct __mavlink_hil_state_quaternion_t -{ - uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - float attitude_quaternion[4]; ///< Vehicle attitude expressed as normalized quaternion - float rollspeed; ///< Body frame roll / phi angular speed (rad/s) - float pitchspeed; ///< Body frame pitch / theta angular speed (rad/s) - float yawspeed; ///< Body frame yaw / psi angular speed (rad/s) - int32_t lat; ///< Latitude, expressed as * 1E7 - int32_t lon; ///< Longitude, expressed as * 1E7 - int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters) - int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100 - int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100 - int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100 - uint16_t ind_airspeed; ///< Indicated airspeed, expressed as m/s * 100 - uint16_t true_airspeed; ///< True airspeed, expressed as m/s * 100 - int16_t xacc; ///< X acceleration (mg) - int16_t yacc; ///< Y acceleration (mg) - int16_t zacc; ///< Z acceleration (mg) -} mavlink_hil_state_quaternion_t; - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64 -#define MAVLINK_MSG_ID_115_LEN 64 - -#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4 -#define MAVLINK_MSG_ID_115_CRC 4 - -#define MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION_LEN 4 - -#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \ - "HIL_STATE_QUATERNION", \ - 16, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \ - { "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \ - { "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \ - { "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \ - { "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \ - { "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \ - { "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \ - { "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \ - } \ -} - - -/** - * @brief Pack a hil_state_quaternion message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 - * @param true_airspeed True airspeed, expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif -} - -/** - * @brief Pack a hil_state_quaternion message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 - * @param true_airspeed True airspeed, expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,const float *attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t ind_airspeed,uint16_t true_airspeed,int16_t xacc,int16_t yacc,int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif -} - -/** - * @brief Encode a hil_state_quaternion struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param hil_state_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ - return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -} - -/** - * @brief Encode a hil_state_quaternion struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param hil_state_quaternion C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ - return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc); -} - -/** - * @brief Send a hil_state_quaternion message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param attitude_quaternion Vehicle attitude expressed as normalized quaternion - * @param rollspeed Body frame roll / phi angular speed (rad/s) - * @param pitchspeed Body frame pitch / theta angular speed (rad/s) - * @param yawspeed Body frame yaw / psi angular speed (rad/s) - * @param lat Latitude, expressed as * 1E7 - * @param lon Longitude, expressed as * 1E7 - * @param alt Altitude in meters, expressed as * 1000 (millimeters) - * @param vx Ground X Speed (Latitude), expressed as m/s * 100 - * @param vy Ground Y Speed (Longitude), expressed as m/s * 100 - * @param vz Ground Z Speed (Altitude), expressed as m/s * 100 - * @param ind_airspeed Indicated airspeed, expressed as m/s * 100 - * @param true_airspeed True airspeed, expressed as m/s * 100 - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_hil_state_quaternion_send(mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif -#else - mavlink_hil_state_quaternion_t packet; - packet.time_usec = time_usec; - packet.rollspeed = rollspeed; - packet.pitchspeed = pitchspeed; - packet.yawspeed = yawspeed; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - packet.ind_airspeed = ind_airspeed; - packet.true_airspeed = true_airspeed; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 24, rollspeed); - _mav_put_float(buf, 28, pitchspeed); - _mav_put_float(buf, 32, yawspeed); - _mav_put_int32_t(buf, 36, lat); - _mav_put_int32_t(buf, 40, lon); - _mav_put_int32_t(buf, 44, alt); - _mav_put_int16_t(buf, 48, vx); - _mav_put_int16_t(buf, 50, vy); - _mav_put_int16_t(buf, 52, vz); - _mav_put_uint16_t(buf, 54, ind_airspeed); - _mav_put_uint16_t(buf, 56, true_airspeed); - _mav_put_int16_t(buf, 58, xacc); - _mav_put_int16_t(buf, 60, yacc); - _mav_put_int16_t(buf, 62, zacc); - _mav_put_float_array(buf, 8, attitude_quaternion, 4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif -#else - mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf; - packet->time_usec = time_usec; - packet->rollspeed = rollspeed; - packet->pitchspeed = pitchspeed; - packet->yawspeed = yawspeed; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - packet->ind_airspeed = ind_airspeed; - packet->true_airspeed = true_airspeed; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE HIL_STATE_QUATERNION UNPACKING - - -/** - * @brief Get field time_usec from hil_state_quaternion message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field attitude_quaternion from hil_state_quaternion message - * - * @return Vehicle attitude expressed as normalized quaternion - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion) -{ - return _MAV_RETURN_float_array(msg, attitude_quaternion, 4, 8); -} - -/** - * @brief Get field rollspeed from hil_state_quaternion message - * - * @return Body frame roll / phi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field pitchspeed from hil_state_quaternion message - * - * @return Body frame pitch / theta angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field yawspeed from hil_state_quaternion message - * - * @return Body frame yaw / psi angular speed (rad/s) - */ -static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field lat from hil_state_quaternion message - * - * @return Latitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 36); -} - -/** - * @brief Get field lon from hil_state_quaternion message - * - * @return Longitude, expressed as * 1E7 - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 40); -} - -/** - * @brief Get field alt from hil_state_quaternion message - * - * @return Altitude in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 44); -} - -/** - * @brief Get field vx from hil_state_quaternion message - * - * @return Ground X Speed (Latitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field vy from hil_state_quaternion message - * - * @return Ground Y Speed (Longitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field vz from hil_state_quaternion message - * - * @return Ground Z Speed (Altitude), expressed as m/s * 100 - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field ind_airspeed from hil_state_quaternion message - * - * @return Indicated airspeed, expressed as m/s * 100 - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 54); -} - -/** - * @brief Get field true_airspeed from hil_state_quaternion message - * - * @return True airspeed, expressed as m/s * 100 - */ -static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 56); -} - -/** - * @brief Get field xacc from hil_state_quaternion message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 58); -} - -/** - * @brief Get field yacc from hil_state_quaternion message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 60); -} - -/** - * @brief Get field zacc from hil_state_quaternion message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 62); -} - -/** - * @brief Decode a hil_state_quaternion message into a struct - * - * @param msg The message to decode - * @param hil_state_quaternion C-struct to decode the message contents into - */ -static inline void mavlink_msg_hil_state_quaternion_decode(const mavlink_message_t* msg, mavlink_hil_state_quaternion_t* hil_state_quaternion) -{ -#if MAVLINK_NEED_BYTE_SWAP - hil_state_quaternion->time_usec = mavlink_msg_hil_state_quaternion_get_time_usec(msg); - mavlink_msg_hil_state_quaternion_get_attitude_quaternion(msg, hil_state_quaternion->attitude_quaternion); - hil_state_quaternion->rollspeed = mavlink_msg_hil_state_quaternion_get_rollspeed(msg); - hil_state_quaternion->pitchspeed = mavlink_msg_hil_state_quaternion_get_pitchspeed(msg); - hil_state_quaternion->yawspeed = mavlink_msg_hil_state_quaternion_get_yawspeed(msg); - hil_state_quaternion->lat = mavlink_msg_hil_state_quaternion_get_lat(msg); - hil_state_quaternion->lon = mavlink_msg_hil_state_quaternion_get_lon(msg); - hil_state_quaternion->alt = mavlink_msg_hil_state_quaternion_get_alt(msg); - hil_state_quaternion->vx = mavlink_msg_hil_state_quaternion_get_vx(msg); - hil_state_quaternion->vy = mavlink_msg_hil_state_quaternion_get_vy(msg); - hil_state_quaternion->vz = mavlink_msg_hil_state_quaternion_get_vz(msg); - hil_state_quaternion->ind_airspeed = mavlink_msg_hil_state_quaternion_get_ind_airspeed(msg); - hil_state_quaternion->true_airspeed = mavlink_msg_hil_state_quaternion_get_true_airspeed(msg); - hil_state_quaternion->xacc = mavlink_msg_hil_state_quaternion_get_xacc(msg); - hil_state_quaternion->yacc = mavlink_msg_hil_state_quaternion_get_yacc(msg); - hil_state_quaternion->zacc = mavlink_msg_hil_state_quaternion_get_zacc(msg); -#else - memcpy(hil_state_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h deleted file mode 100644 index e18a94869..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE LOCAL_POSITION_NED PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32 - -typedef struct __mavlink_local_position_ned_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - float x; ///< X Position - float y; ///< Y Position - float z; ///< Z Position - float vx; ///< X Speed - float vy; ///< Y Speed - float vz; ///< Z Speed -} mavlink_local_position_ned_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28 -#define MAVLINK_MSG_ID_32_LEN 28 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC 185 -#define MAVLINK_MSG_ID_32_CRC 185 - - - -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \ - "LOCAL_POSITION_NED", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \ - { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \ - { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \ - { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \ - } \ -} - - -/** - * @brief Pack a local_position_ned message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#else - mavlink_local_position_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif -} - -/** - * @brief Pack a local_position_ned message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#else - mavlink_local_position_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif -} - -/** - * @brief Encode a local_position_ned struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) -{ - return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -} - -/** - * @brief Encode a local_position_ned struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned) -{ - return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz); -} - -/** - * @brief Send a local_position_ned message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param vx X Speed - * @param vy Y Speed - * @param vz Z Speed - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif -#else - mavlink_local_position_ned_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.vx = vx; - packet.vy = vy; - packet.vz = vz; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, vx); - _mav_put_float(buf, 20, vy); - _mav_put_float(buf, 24, vz); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif -#else - mavlink_local_position_ned_t *packet = (mavlink_local_position_ned_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->vx = vx; - packet->vy = vy; - packet->vz = vz; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED UNPACKING - - -/** - * @brief Get field time_boot_ms from local_position_ned message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field x from local_position_ned message - * - * @return X Position - */ -static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from local_position_ned message - * - * @return Y Position - */ -static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from local_position_ned message - * - * @return Z Position - */ -static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field vx from local_position_ned message - * - * @return X Speed - */ -static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field vy from local_position_ned message - * - * @return Y Speed - */ -static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vz from local_position_ned message - * - * @return Z Speed - */ -static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a local_position_ned message into a struct - * - * @param msg The message to decode - * @param local_position_ned C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned) -{ -#if MAVLINK_NEED_BYTE_SWAP - local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg); - local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg); - local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg); - local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg); - local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg); - local_position_ned->vy = mavlink_msg_local_position_ned_get_vy(msg); - local_position_ned->vz = mavlink_msg_local_position_ned_get_vz(msg); -#else - memcpy(local_position_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h deleted file mode 100644 index af7d195b0..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89 - -typedef struct __mavlink_local_position_ned_system_global_offset_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - float x; ///< X Position - float y; ///< Y Position - float z; ///< Z Position - float roll; ///< Roll - float pitch; ///< Pitch - float yaw; ///< Yaw -} mavlink_local_position_ned_system_global_offset_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28 -#define MAVLINK_MSG_ID_89_LEN 28 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231 -#define MAVLINK_MSG_ID_89_CRC 231 - - - -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \ - "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \ - } \ -} - - -/** - * @brief Pack a local_position_ned_system_global_offset message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#else - mavlink_local_position_ned_system_global_offset_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif -} - -/** - * @brief Pack a local_position_ned_system_global_offset message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#else - mavlink_local_position_ned_system_global_offset_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif -} - -/** - * @brief Encode a local_position_ned_system_global_offset struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_system_global_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ - return mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -} - -/** - * @brief Encode a local_position_ned_system_global_offset struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_ned_system_global_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ - return mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, chan, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw); -} - -/** - * @brief Send a local_position_ned_system_global_offset message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param roll Roll - * @param pitch Pitch - * @param yaw Yaw - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif -#else - mavlink_local_position_ned_system_global_offset_t packet; - packet.time_boot_ms = time_boot_ms; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, x); - _mav_put_float(buf, 8, y); - _mav_put_float(buf, 12, z); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif -#else - mavlink_local_position_ned_system_global_offset_t *packet = (mavlink_local_position_ned_system_global_offset_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET UNPACKING - - -/** - * @brief Get field time_boot_ms from local_position_ned_system_global_offset message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field x from local_position_ned_system_global_offset message - * - * @return X Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field y from local_position_ned_system_global_offset message - * - * @return Y Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field z from local_position_ned_system_global_offset message - * - * @return Z Position - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field roll from local_position_ned_system_global_offset message - * - * @return Roll - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitch from local_position_ned_system_global_offset message - * - * @return Pitch - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yaw from local_position_ned_system_global_offset message - * - * @return Yaw - */ -static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a local_position_ned_system_global_offset message into a struct - * - * @param msg The message to decode - * @param local_position_ned_system_global_offset C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_ned_system_global_offset_decode(const mavlink_message_t* msg, mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset) -{ -#if MAVLINK_NEED_BYTE_SWAP - local_position_ned_system_global_offset->time_boot_ms = mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(msg); - local_position_ned_system_global_offset->x = mavlink_msg_local_position_ned_system_global_offset_get_x(msg); - local_position_ned_system_global_offset->y = mavlink_msg_local_position_ned_system_global_offset_get_y(msg); - local_position_ned_system_global_offset->z = mavlink_msg_local_position_ned_system_global_offset_get_z(msg); - local_position_ned_system_global_offset->roll = mavlink_msg_local_position_ned_system_global_offset_get_roll(msg); - local_position_ned_system_global_offset->pitch = mavlink_msg_local_position_ned_system_global_offset_get_pitch(msg); - local_position_ned_system_global_offset->yaw = mavlink_msg_local_position_ned_system_global_offset_get_yaw(msg); -#else - memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h deleted file mode 100644 index 8dae721be..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE LOCAL_POSITION_SETPOINT PACKING - -#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51 - -typedef struct __mavlink_local_position_setpoint_t -{ - float x; ///< x position - float y; ///< y position - float z; ///< z position - float yaw; ///< Desired yaw angle - uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU -} mavlink_local_position_setpoint_t; - -#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17 -#define MAVLINK_MSG_ID_51_LEN 17 - -#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC 223 -#define MAVLINK_MSG_ID_51_CRC 223 - - - -#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT { \ - "LOCAL_POSITION_SETPOINT", \ - 5, \ - { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_local_position_setpoint_t, coordinate_frame) }, \ - } \ -} - - -/** - * @brief Pack a local_position_setpoint message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - * @param x x position - * @param y y position - * @param z z position - * @param yaw Desired yaw angle - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t coordinate_frame, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#else - mavlink_local_position_setpoint_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#endif -} - -/** - * @brief Pack a local_position_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - * @param x x position - * @param y y position - * @param z z position - * @param yaw Desired yaw angle - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t coordinate_frame,float x,float y,float z,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#else - mavlink_local_position_setpoint_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#endif -} - -/** - * @brief Encode a local_position_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param local_position_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint) -{ - return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->coordinate_frame, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw); -} - -/** - * @brief Encode a local_position_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param local_position_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_local_position_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint) -{ - return mavlink_msg_local_position_setpoint_pack_chan(system_id, component_id, chan, msg, local_position_setpoint->coordinate_frame, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw); -} - -/** - * @brief Send a local_position_setpoint message - * @param chan MAVLink channel to send the message - * - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - * @param x x position - * @param y y position - * @param z z position - * @param yaw Desired yaw angle - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, uint8_t coordinate_frame, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, coordinate_frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#endif -#else - mavlink_local_position_setpoint_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.coordinate_frame = coordinate_frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_local_position_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t coordinate_frame, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, coordinate_frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#endif -#else - mavlink_local_position_setpoint_t *packet = (mavlink_local_position_setpoint_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->yaw = yaw; - packet->coordinate_frame = coordinate_frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING - - -/** - * @brief Get field coordinate_frame from local_position_setpoint message - * - * @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - */ -static inline uint8_t mavlink_msg_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field x from local_position_setpoint message - * - * @return x position - */ -static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field y from local_position_setpoint message - * - * @return y position - */ -static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field z from local_position_setpoint message - * - * @return z position - */ -static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from local_position_setpoint message - * - * @return Desired yaw angle - */ -static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a local_position_setpoint message into a struct - * - * @param msg The message to decode - * @param local_position_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP - local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg); - local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg); - local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg); - local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg); - local_position_setpoint->coordinate_frame = mavlink_msg_local_position_setpoint_get_coordinate_frame(msg); -#else - memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h deleted file mode 100644 index 48641f3eb..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_data.h +++ /dev/null @@ -1,273 +0,0 @@ -// MESSAGE LOG_DATA PACKING - -#define MAVLINK_MSG_ID_LOG_DATA 120 - -typedef struct __mavlink_log_data_t -{ - uint32_t ofs; ///< Offset into the log - uint16_t id; ///< Log id (from LOG_ENTRY reply) - uint8_t count; ///< Number of bytes (zero for end of log) - uint8_t data[90]; ///< log data -} mavlink_log_data_t; - -#define MAVLINK_MSG_ID_LOG_DATA_LEN 97 -#define MAVLINK_MSG_ID_120_LEN 97 - -#define MAVLINK_MSG_ID_LOG_DATA_CRC 134 -#define MAVLINK_MSG_ID_120_CRC 134 - -#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN 90 - -#define MAVLINK_MESSAGE_INFO_LOG_DATA { \ - "LOG_DATA", \ - 4, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \ - } \ -} - - -/** - * @brief Pack a log_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_DATA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif -} - -/** - * @brief Pack a log_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,uint32_t ofs,uint8_t count,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_DATA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif -} - -/** - * @brief Encode a log_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_data_t* log_data) -{ - return mavlink_msg_log_data_pack(system_id, component_id, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); -} - -/** - * @brief Encode a log_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_data_t* log_data) -{ - return mavlink_msg_log_data_pack_chan(system_id, component_id, chan, msg, log_data->id, log_data->ofs, log_data->count, log_data->data); -} - -/** - * @brief Send a log_data message - * @param chan MAVLink channel to send the message - * - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes (zero for end of log) - * @param data log data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif -#else - mavlink_log_data_t packet; - packet.ofs = ofs; - packet.id = id; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LOG_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint16_t(buf, 4, id); - _mav_put_uint8_t(buf, 6, count); - _mav_put_uint8_t_array(buf, 7, data, 90); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif -#else - mavlink_log_data_t *packet = (mavlink_log_data_t *)msgbuf; - packet->ofs = ofs; - packet->id = id; - packet->count = count; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*90); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LOG_DATA UNPACKING - - -/** - * @brief Get field id from log_data message - * - * @return Log id (from LOG_ENTRY reply) - */ -static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field ofs from log_data message - * - * @return Offset into the log - */ -static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from log_data message - * - * @return Number of bytes (zero for end of log) - */ -static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field data from log_data message - * - * @return log data - */ -static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 90, 7); -} - -/** - * @brief Decode a log_data message into a struct - * - * @param msg The message to decode - * @param log_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_data_decode(const mavlink_message_t* msg, mavlink_log_data_t* log_data) -{ -#if MAVLINK_NEED_BYTE_SWAP - log_data->ofs = mavlink_msg_log_data_get_ofs(msg); - log_data->id = mavlink_msg_log_data_get_id(msg); - log_data->count = mavlink_msg_log_data_get_count(msg); - mavlink_msg_log_data_get_data(msg, log_data->data); -#else - memcpy(log_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_DATA_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h deleted file mode 100644 index 8ecaec3ae..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_entry.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE LOG_ENTRY PACKING - -#define MAVLINK_MSG_ID_LOG_ENTRY 118 - -typedef struct __mavlink_log_entry_t -{ - uint32_t time_utc; ///< UTC timestamp of log in seconds since 1970, or 0 if not available - uint32_t size; ///< Size of the log (may be approximate) in bytes - uint16_t id; ///< Log id - uint16_t num_logs; ///< Total number of logs - uint16_t last_log_num; ///< High log number -} mavlink_log_entry_t; - -#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14 -#define MAVLINK_MSG_ID_118_LEN 14 - -#define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56 -#define MAVLINK_MSG_ID_118_CRC 56 - - - -#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \ - "LOG_ENTRY", \ - 5, \ - { { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \ - { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \ - { "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \ - { "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \ - } \ -} - - -/** - * @brief Pack a log_entry message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif -} - -/** - * @brief Pack a log_entry message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,uint16_t num_logs,uint16_t last_log_num,uint32_t time_utc,uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif -} - -/** - * @brief Encode a log_entry struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_entry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_entry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) -{ - return mavlink_msg_log_entry_pack(system_id, component_id, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -} - -/** - * @brief Encode a log_entry struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_entry C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry) -{ - return mavlink_msg_log_entry_pack_chan(system_id, component_id, chan, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size); -} - -/** - * @brief Send a log_entry message - * @param chan MAVLink channel to send the message - * - * @param id Log id - * @param num_logs Total number of logs - * @param last_log_num High log number - * @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available - * @param size Size of the log (may be approximate) in bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_entry_send(mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN]; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif -#else - mavlink_log_entry_t packet; - packet.time_utc = time_utc; - packet.size = size; - packet.id = id; - packet.num_logs = num_logs; - packet.last_log_num = last_log_num; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LOG_ENTRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_entry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_utc); - _mav_put_uint32_t(buf, 4, size); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint16_t(buf, 10, num_logs); - _mav_put_uint16_t(buf, 12, last_log_num); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif -#else - mavlink_log_entry_t *packet = (mavlink_log_entry_t *)msgbuf; - packet->time_utc = time_utc; - packet->size = size; - packet->id = id; - packet->num_logs = num_logs; - packet->last_log_num = last_log_num; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LOG_ENTRY UNPACKING - - -/** - * @brief Get field id from log_entry message - * - * @return Log id - */ -static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field num_logs from log_entry message - * - * @return Total number of logs - */ -static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field last_log_num from log_entry message - * - * @return High log number - */ -static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field time_utc from log_entry message - * - * @return UTC timestamp of log in seconds since 1970, or 0 if not available - */ -static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field size from log_entry message - * - * @return Size of the log (may be approximate) in bytes - */ -static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Decode a log_entry message into a struct - * - * @param msg The message to decode - * @param log_entry C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_entry_decode(const mavlink_message_t* msg, mavlink_log_entry_t* log_entry) -{ -#if MAVLINK_NEED_BYTE_SWAP - log_entry->time_utc = mavlink_msg_log_entry_get_time_utc(msg); - log_entry->size = mavlink_msg_log_entry_get_size(msg); - log_entry->id = mavlink_msg_log_entry_get_id(msg); - log_entry->num_logs = mavlink_msg_log_entry_get_num_logs(msg); - log_entry->last_log_num = mavlink_msg_log_entry_get_last_log_num(msg); -#else - memcpy(log_entry, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ENTRY_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h deleted file mode 100644 index 957c4d4cc..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_erase.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE LOG_ERASE PACKING - -#define MAVLINK_MSG_ID_LOG_ERASE 121 - -typedef struct __mavlink_log_erase_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_log_erase_t; - -#define MAVLINK_MSG_ID_LOG_ERASE_LEN 2 -#define MAVLINK_MSG_ID_121_LEN 2 - -#define MAVLINK_MSG_ID_LOG_ERASE_CRC 237 -#define MAVLINK_MSG_ID_121_CRC 237 - - - -#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \ - "LOG_ERASE", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a log_erase message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_erase_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif -} - -/** - * @brief Pack a log_erase message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_erase_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_ERASE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif -} - -/** - * @brief Encode a log_erase struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_erase C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_erase_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) -{ - return mavlink_msg_log_erase_pack(system_id, component_id, msg, log_erase->target_system, log_erase->target_component); -} - -/** - * @brief Encode a log_erase struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_erase C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_erase_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase) -{ - return mavlink_msg_log_erase_pack_chan(system_id, component_id, chan, msg, log_erase->target_system, log_erase->target_component); -} - -/** - * @brief Send a log_erase message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_erase_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif -#else - mavlink_log_erase_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LOG_ERASE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_erase_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif -#else - mavlink_log_erase_t *packet = (mavlink_log_erase_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LOG_ERASE UNPACKING - - -/** - * @brief Get field target_system from log_erase message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from log_erase message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_erase_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a log_erase message into a struct - * - * @param msg The message to decode - * @param log_erase C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_erase_decode(const mavlink_message_t* msg, mavlink_log_erase_t* log_erase) -{ -#if MAVLINK_NEED_BYTE_SWAP - log_erase->target_system = mavlink_msg_log_erase_get_target_system(msg); - log_erase->target_component = mavlink_msg_log_erase_get_target_component(msg); -#else - memcpy(log_erase, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ERASE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h deleted file mode 100644 index ef5cbb67c..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_data.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE LOG_REQUEST_DATA PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119 - -typedef struct __mavlink_log_request_data_t -{ - uint32_t ofs; ///< Offset into the log - uint32_t count; ///< Number of bytes - uint16_t id; ///< Log id (from LOG_ENTRY reply) - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_log_request_data_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12 -#define MAVLINK_MSG_ID_119_LEN 12 - -#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116 -#define MAVLINK_MSG_ID_119_CRC 116 - - - -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \ - "LOG_REQUEST_DATA", \ - 5, \ - { { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \ - { "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a log_request_data message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif -} - -/** - * @brief Pack a log_request_data message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t id,uint32_t ofs,uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif -} - -/** - * @brief Encode a log_request_data struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) -{ - return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -} - -/** - * @brief Encode a log_request_data struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_data C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data) -{ - return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count); -} - -/** - * @brief Send a log_request_data message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param id Log id (from LOG_ENTRY reply) - * @param ofs Offset into the log - * @param count Number of bytes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN]; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif -#else - mavlink_log_request_data_t packet; - packet.ofs = ofs; - packet.count = count; - packet.id = id; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, ofs); - _mav_put_uint32_t(buf, 4, count); - _mav_put_uint16_t(buf, 8, id); - _mav_put_uint8_t(buf, 10, target_system); - _mav_put_uint8_t(buf, 11, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif -#else - mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf; - packet->ofs = ofs; - packet->count = count; - packet->id = id; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_DATA UNPACKING - - -/** - * @brief Get field target_system from log_request_data message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field target_component from log_request_data message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field id from log_request_data message - * - * @return Log id (from LOG_ENTRY reply) - */ -static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field ofs from log_request_data message - * - * @return Offset into the log - */ -static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from log_request_data message - * - * @return Number of bytes - */ -static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Decode a log_request_data message into a struct - * - * @param msg The message to decode - * @param log_request_data C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_data_decode(const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data) -{ -#if MAVLINK_NEED_BYTE_SWAP - log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg); - log_request_data->count = mavlink_msg_log_request_data_get_count(msg); - log_request_data->id = mavlink_msg_log_request_data_get_id(msg); - log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg); - log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg); -#else - memcpy(log_request_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h deleted file mode 100644 index 23fcca29f..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_end.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE LOG_REQUEST_END PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_END 122 - -typedef struct __mavlink_log_request_end_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_log_request_end_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2 -#define MAVLINK_MSG_ID_122_LEN 2 - -#define MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203 -#define MAVLINK_MSG_ID_122_CRC 203 - - - -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \ - "LOG_REQUEST_END", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a log_request_end message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_end_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif -} - -/** - * @brief Pack a log_request_end message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_end_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif -} - -/** - * @brief Encode a log_request_end struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_end C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_end_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) -{ - return mavlink_msg_log_request_end_pack(system_id, component_id, msg, log_request_end->target_system, log_request_end->target_component); -} - -/** - * @brief Encode a log_request_end struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_end C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_end_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end) -{ - return mavlink_msg_log_request_end_pack_chan(system_id, component_id, chan, msg, log_request_end->target_system, log_request_end->target_component); -} - -/** - * @brief Send a log_request_end message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_end_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif -#else - mavlink_log_request_end_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_END_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_end_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif -#else - mavlink_log_request_end_t *packet = (mavlink_log_request_end_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_END UNPACKING - - -/** - * @brief Get field target_system from log_request_end message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from log_request_end message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_end_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a log_request_end message into a struct - * - * @param msg The message to decode - * @param log_request_end C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_end_decode(const mavlink_message_t* msg, mavlink_log_request_end_t* log_request_end) -{ -#if MAVLINK_NEED_BYTE_SWAP - log_request_end->target_system = mavlink_msg_log_request_end_get_target_system(msg); - log_request_end->target_component = mavlink_msg_log_request_end_get_target_component(msg); -#else - memcpy(log_request_end, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_END_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h deleted file mode 100644 index e511b5312..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_log_request_list.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE LOG_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117 - -typedef struct __mavlink_log_request_list_t -{ - uint16_t start; ///< First log id (0 for first available) - uint16_t end; ///< Last log id (0xffff for last available) - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_log_request_list_t; - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6 -#define MAVLINK_MSG_ID_117_LEN 6 - -#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128 -#define MAVLINK_MSG_ID_117_CRC 128 - - - -#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \ - "LOG_REQUEST_LIST", \ - 4, \ - { { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \ - { "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a log_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif -} - -/** - * @brief Pack a log_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_log_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t start,uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif -} - -/** - * @brief Encode a log_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param log_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) -{ - return mavlink_msg_log_request_list_pack(system_id, component_id, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -} - -/** - * @brief Encode a log_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param log_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_log_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list) -{ - return mavlink_msg_log_request_list_pack_chan(system_id, component_id, chan, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end); -} - -/** - * @brief Send a log_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start First log id (0 for first available) - * @param end Last log id (0xffff for last available) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_log_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN]; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif -#else - mavlink_log_request_list_t packet; - packet.start = start; - packet.end = end; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_log_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, start); - _mav_put_uint16_t(buf, 2, end); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif -#else - mavlink_log_request_list_t *packet = (mavlink_log_request_list_t *)msgbuf; - packet->start = start; - packet->end = end; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LOG_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from log_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from log_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_log_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start from log_request_list message - * - * @return First log id (0 for first available) - */ -static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field end from log_request_list message - * - * @return Last log id (0xffff for last available) - */ -static inline uint16_t mavlink_msg_log_request_list_get_end(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a log_request_list message into a struct - * - * @param msg The message to decode - * @param log_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_log_request_list_decode(const mavlink_message_t* msg, mavlink_log_request_list_t* log_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP - log_request_list->start = mavlink_msg_log_request_list_get_start(msg); - log_request_list->end = mavlink_msg_log_request_list_get_end(msg); - log_request_list->target_system = mavlink_msg_log_request_list_get_target_system(msg); - log_request_list->target_component = mavlink_msg_log_request_list_get_target_component(msg); -#else - memcpy(log_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h deleted file mode 100644 index e93b759d0..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE MANUAL_CONTROL PACKING - -#define MAVLINK_MSG_ID_MANUAL_CONTROL 69 - -typedef struct __mavlink_manual_control_t -{ - int16_t x; ///< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - int16_t y; ///< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - int16_t z; ///< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. - int16_t r; ///< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - uint16_t buttons; ///< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - uint8_t target; ///< The system to be controlled. -} mavlink_manual_control_t; - -#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11 -#define MAVLINK_MSG_ID_69_LEN 11 - -#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243 -#define MAVLINK_MSG_ID_69_CRC 243 - - - -#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \ - "MANUAL_CONTROL", \ - 6, \ - { { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \ - { "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \ - { "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \ - { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \ - } \ -} - - -/** - * @brief Pack a manual_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif -} - -/** - * @brief Pack a manual_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target,int16_t x,int16_t y,int16_t z,int16_t r,uint16_t buttons) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif -} - -/** - * @brief Encode a manual_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) -{ - return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); -} - -/** - * @brief Encode a manual_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param manual_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control) -{ - return mavlink_msg_manual_control_pack_chan(system_id, component_id, chan, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons); -} - -/** - * @brief Send a manual_control message - * @param chan MAVLink channel to send the message - * - * @param target The system to be controlled. - * @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - * @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - * @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. - * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - * @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN]; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif -#else - mavlink_manual_control_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.r = r; - packet.buttons = buttons; - packet.target = target; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, x); - _mav_put_int16_t(buf, 2, y); - _mav_put_int16_t(buf, 4, z); - _mav_put_int16_t(buf, 6, r); - _mav_put_uint16_t(buf, 8, buttons); - _mav_put_uint8_t(buf, 10, target); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif -#else - mavlink_manual_control_t *packet = (mavlink_manual_control_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->r = r; - packet->buttons = buttons; - packet->target = target; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MANUAL_CONTROL UNPACKING - - -/** - * @brief Get field target from manual_control message - * - * @return The system to be controlled. - */ -static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field x from manual_control message - * - * @return X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field y from manual_control message - * - * @return Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Get field z from manual_control message - * - * @return Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field r from manual_control message - * - * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle. - */ -static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field buttons from manual_control message - * - * @return A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1. - */ -static inline uint16_t mavlink_msg_manual_control_get_buttons(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Decode a manual_control message into a struct - * - * @param msg The message to decode - * @param manual_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control) -{ -#if MAVLINK_NEED_BYTE_SWAP - manual_control->x = mavlink_msg_manual_control_get_x(msg); - manual_control->y = mavlink_msg_manual_control_get_y(msg); - manual_control->z = mavlink_msg_manual_control_get_z(msg); - manual_control->r = mavlink_msg_manual_control_get_r(msg); - manual_control->buttons = mavlink_msg_manual_control_get_buttons(msg); - manual_control->target = mavlink_msg_manual_control_get_target(msg); -#else - memcpy(manual_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_CONTROL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h deleted file mode 100644 index b27626726..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_manual_setpoint.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE MANUAL_SETPOINT PACKING - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81 - -typedef struct __mavlink_manual_setpoint_t -{ - uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot - float roll; ///< Desired roll rate in radians per second - float pitch; ///< Desired pitch rate in radians per second - float yaw; ///< Desired yaw rate in radians per second - float thrust; ///< Collective thrust, normalized to 0 .. 1 - uint8_t mode_switch; ///< Flight mode switch position, 0.. 255 - uint8_t manual_override_switch; ///< Override mode switch position, 0.. 255 -} mavlink_manual_setpoint_t; - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22 -#define MAVLINK_MSG_ID_81_LEN 22 - -#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106 -#define MAVLINK_MSG_ID_81_CRC 106 - - - -#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \ - "MANUAL_SETPOINT", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \ - { "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \ - { "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \ - } \ -} - - -/** - * @brief Pack a manual_setpoint message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#else - mavlink_manual_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif -} - -/** - * @brief Pack a manual_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_manual_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust,uint8_t mode_switch,uint8_t manual_override_switch) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#else - mavlink_manual_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif -} - -/** - * @brief Encode a manual_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param manual_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) -{ - return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -} - -/** - * @brief Encode a manual_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param manual_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint) -{ - return mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, chan, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch); -} - -/** - * @brief Send a manual_setpoint message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll rate in radians per second - * @param pitch Desired pitch rate in radians per second - * @param yaw Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @param mode_switch Flight mode switch position, 0.. 255 - * @param manual_override_switch Override mode switch position, 0.. 255 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif -#else - mavlink_manual_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.mode_switch = mode_switch; - packet.manual_override_switch = manual_override_switch; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - _mav_put_uint8_t(buf, 20, mode_switch); - _mav_put_uint8_t(buf, 21, manual_override_switch); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif -#else - mavlink_manual_setpoint_t *packet = (mavlink_manual_setpoint_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->thrust = thrust; - packet->mode_switch = mode_switch; - packet->manual_override_switch = manual_override_switch; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MANUAL_SETPOINT UNPACKING - - -/** - * @brief Get field time_boot_ms from manual_setpoint message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from manual_setpoint message - * - * @return Desired roll rate in radians per second - */ -static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from manual_setpoint message - * - * @return Desired pitch rate in radians per second - */ -static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from manual_setpoint message - * - * @return Desired yaw rate in radians per second - */ -static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field thrust from manual_setpoint message - * - * @return Collective thrust, normalized to 0 .. 1 - */ -static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field mode_switch from manual_setpoint message - * - * @return Flight mode switch position, 0.. 255 - */ -static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field manual_override_switch from manual_setpoint message - * - * @return Override mode switch position, 0.. 255 - */ -static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a manual_setpoint message into a struct - * - * @param msg The message to decode - * @param manual_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP - manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg); - manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg); - manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg); - manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg); - manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg); - manual_setpoint->mode_switch = mavlink_msg_manual_setpoint_get_mode_switch(msg); - manual_setpoint->manual_override_switch = mavlink_msg_manual_setpoint_get_manual_override_switch(msg); -#else - memcpy(manual_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h deleted file mode 100644 index 2eb60cc0e..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h +++ /dev/null @@ -1,273 +0,0 @@ -// MESSAGE MEMORY_VECT PACKING - -#define MAVLINK_MSG_ID_MEMORY_VECT 249 - -typedef struct __mavlink_memory_vect_t -{ - uint16_t address; ///< Starting address of the debug variables - uint8_t ver; ///< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - uint8_t type; ///< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - int8_t value[32]; ///< Memory contents at specified address -} mavlink_memory_vect_t; - -#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36 -#define MAVLINK_MSG_ID_249_LEN 36 - -#define MAVLINK_MSG_ID_MEMORY_VECT_CRC 204 -#define MAVLINK_MSG_ID_249_CRC 204 - -#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32 - -#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \ - "MEMORY_VECT", \ - 4, \ - { { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \ - { "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \ - { "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \ - } \ -} - - -/** - * @brief Pack a memory_vect message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; - _mav_put_uint16_t(buf, 0, address); - _mav_put_uint8_t(buf, 2, ver); - _mav_put_uint8_t(buf, 3, type); - _mav_put_int8_t_array(buf, 4, value, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#else - mavlink_memory_vect_t packet; - packet.address = address; - packet.ver = ver; - packet.type = type; - mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif -} - -/** - * @brief Pack a memory_vect message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t address,uint8_t ver,uint8_t type,const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; - _mav_put_uint16_t(buf, 0, address); - _mav_put_uint8_t(buf, 2, ver); - _mav_put_uint8_t(buf, 3, type); - _mav_put_int8_t_array(buf, 4, value, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#else - mavlink_memory_vect_t packet; - packet.address = address; - packet.ver = ver; - packet.type = type; - mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif -} - -/** - * @brief Encode a memory_vect struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param memory_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) -{ - return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -} - -/** - * @brief Encode a memory_vect struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param memory_vect C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_memory_vect_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect) -{ - return mavlink_msg_memory_vect_pack_chan(system_id, component_id, chan, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value); -} - -/** - * @brief Send a memory_vect message - * @param chan MAVLink channel to send the message - * - * @param address Starting address of the debug variables - * @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - * @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - * @param value Memory contents at specified address - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MEMORY_VECT_LEN]; - _mav_put_uint16_t(buf, 0, address); - _mav_put_uint8_t(buf, 2, ver); - _mav_put_uint8_t(buf, 3, type); - _mav_put_int8_t_array(buf, 4, value, 32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif -#else - mavlink_memory_vect_t packet; - packet.address = address; - packet.ver = ver; - packet.type = type; - mav_array_memcpy(packet.value, value, sizeof(int8_t)*32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MEMORY_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_memory_vect_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, address); - _mav_put_uint8_t(buf, 2, ver); - _mav_put_uint8_t(buf, 3, type); - _mav_put_int8_t_array(buf, 4, value, 32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif -#else - mavlink_memory_vect_t *packet = (mavlink_memory_vect_t *)msgbuf; - packet->address = address; - packet->ver = ver; - packet->type = type; - mav_array_memcpy(packet->value, value, sizeof(int8_t)*32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MEMORY_VECT UNPACKING - - -/** - * @brief Get field address from memory_vect message - * - * @return Starting address of the debug variables - */ -static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field ver from memory_vect message - * - * @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below - */ -static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field type from memory_vect message - * - * @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 - */ -static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field value from memory_vect message - * - * @return Memory contents at specified address - */ -static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value) -{ - return _MAV_RETURN_int8_t_array(msg, value, 32, 4); -} - -/** - * @brief Decode a memory_vect message into a struct - * - * @param msg The message to decode - * @param memory_vect C-struct to decode the message contents into - */ -static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect) -{ -#if MAVLINK_NEED_BYTE_SWAP - memory_vect->address = mavlink_msg_memory_vect_get_address(msg); - memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg); - memory_vect->type = mavlink_msg_memory_vect_get_type(msg); - mavlink_msg_memory_vect_get_value(msg, memory_vect->value); -#else - memcpy(memory_vect, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MEMORY_VECT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h deleted file mode 100644 index 43afd00f7..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE MISSION_ACK PACKING - -#define MAVLINK_MSG_ID_MISSION_ACK 47 - -typedef struct __mavlink_mission_ack_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t type; ///< See MAV_MISSION_RESULT enum -} mavlink_mission_ack_t; - -#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3 -#define MAVLINK_MSG_ID_47_LEN 3 - -#define MAVLINK_MSG_ID_MISSION_ACK_CRC 153 -#define MAVLINK_MSG_ID_47_CRC 153 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \ - "MISSION_ACK", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \ - } \ -} - - -/** - * @brief Pack a mission_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#else - mavlink_mission_ack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type = type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif -} - -/** - * @brief Pack a mission_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#else - mavlink_mission_ack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type = type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif -} - -/** - * @brief Encode a mission_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) -{ - return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); -} - -/** - * @brief Encode a mission_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack) -{ - return mavlink_msg_mission_ack_pack_chan(system_id, component_id, chan, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type); -} - -/** - * @brief Send a mission_ack message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param type See MAV_MISSION_RESULT enum - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ACK_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, type); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif -#else - mavlink_mission_ack_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.type = type; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, type); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif -#else - mavlink_mission_ack_t *packet = (mavlink_mission_ack_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->type = type; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ACK UNPACKING - - -/** - * @brief Get field target_system from mission_ack message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_ack message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field type from mission_ack message - * - * @return See MAV_MISSION_RESULT enum - */ -static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a mission_ack message into a struct - * - * @param msg The message to decode - * @param mission_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg); - mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg); - mission_ack->type = mavlink_msg_mission_ack_get_type(msg); -#else - memcpy(mission_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ACK_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h deleted file mode 100644 index 120986873..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE MISSION_CLEAR_ALL PACKING - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45 - -typedef struct __mavlink_mission_clear_all_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_mission_clear_all_t; - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2 -#define MAVLINK_MSG_ID_45_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232 -#define MAVLINK_MSG_ID_45_CRC 232 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \ - "MISSION_CLEAR_ALL", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a mission_clear_all message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#else - mavlink_mission_clear_all_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif -} - -/** - * @brief Pack a mission_clear_all message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#else - mavlink_mission_clear_all_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif -} - -/** - * @brief Encode a mission_clear_all struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_clear_all C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) -{ - return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component); -} - -/** - * @brief Encode a mission_clear_all struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_clear_all C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_clear_all_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all) -{ - return mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, chan, msg, mission_clear_all->target_system, mission_clear_all->target_component); -} - -/** - * @brief Send a mission_clear_all message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif -#else - mavlink_mission_clear_all_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_clear_all_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif -#else - mavlink_mission_clear_all_t *packet = (mavlink_mission_clear_all_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_CLEAR_ALL UNPACKING - - -/** - * @brief Get field target_system from mission_clear_all message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_clear_all message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a mission_clear_all message into a struct - * - * @param msg The message to decode - * @param mission_clear_all C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_clear_all->target_system = mavlink_msg_mission_clear_all_get_target_system(msg); - mission_clear_all->target_component = mavlink_msg_mission_clear_all_get_target_component(msg); -#else - memcpy(mission_clear_all, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h deleted file mode 100644 index 7e4748eae..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE MISSION_COUNT PACKING - -#define MAVLINK_MSG_ID_MISSION_COUNT 44 - -typedef struct __mavlink_mission_count_t -{ - uint16_t count; ///< Number of mission items in the sequence - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_mission_count_t; - -#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4 -#define MAVLINK_MSG_ID_44_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221 -#define MAVLINK_MSG_ID_44_CRC 221 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \ - "MISSION_COUNT", \ - 3, \ - { { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a mission_count message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; - _mav_put_uint16_t(buf, 0, count); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#else - mavlink_mission_count_t packet; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif -} - -/** - * @brief Pack a mission_count message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; - _mav_put_uint16_t(buf, 0, count); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#else - mavlink_mission_count_t packet; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif -} - -/** - * @brief Encode a mission_count struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_count C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) -{ - return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count); -} - -/** - * @brief Encode a mission_count struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_count C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count) -{ - return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, msg, mission_count->target_system, mission_count->target_component, mission_count->count); -} - -/** - * @brief Send a mission_count message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param count Number of mission items in the sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_COUNT_LEN]; - _mav_put_uint16_t(buf, 0, count); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif -#else - mavlink_mission_count_t packet; - packet.count = count; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, count); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif -#else - mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf; - packet->count = count; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_COUNT UNPACKING - - -/** - * @brief Get field target_system from mission_count message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_count message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field count from mission_count message - * - * @return Number of mission items in the sequence - */ -static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_count message into a struct - * - * @param msg The message to decode - * @param mission_count C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_count->count = mavlink_msg_mission_count_get_count(msg); - mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg); - mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg); -#else - memcpy(mission_count, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_COUNT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h deleted file mode 100644 index 201b7a6fb..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h +++ /dev/null @@ -1,209 +0,0 @@ -// MESSAGE MISSION_CURRENT PACKING - -#define MAVLINK_MSG_ID_MISSION_CURRENT 42 - -typedef struct __mavlink_mission_current_t -{ - uint16_t seq; ///< Sequence -} mavlink_mission_current_t; - -#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2 -#define MAVLINK_MSG_ID_42_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_CURRENT_CRC 28 -#define MAVLINK_MSG_ID_42_CRC 28 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \ - "MISSION_CURRENT", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \ - } \ -} - - -/** - * @brief Pack a mission_current message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#else - mavlink_mission_current_t packet; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif -} - -/** - * @brief Pack a mission_current message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#else - mavlink_mission_current_t packet; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif -} - -/** - * @brief Encode a mission_current struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) -{ - return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq); -} - -/** - * @brief Encode a mission_current struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current) -{ - return mavlink_msg_mission_current_pack_chan(system_id, component_id, chan, msg, mission_current->seq); -} - -/** - * @brief Send a mission_current message - * @param chan MAVLink channel to send the message - * - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif -#else - mavlink_mission_current_t packet; - packet.seq = seq; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif -#else - mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf; - packet->seq = seq; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_CURRENT UNPACKING - - -/** - * @brief Get field seq from mission_current message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_current message into a struct - * - * @param msg The message to decode - * @param mission_current C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_current->seq = mavlink_msg_mission_current_get_seq(msg); -#else - memcpy(mission_current, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_CURRENT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h deleted file mode 100644 index ef9394f00..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h +++ /dev/null @@ -1,521 +0,0 @@ -// MESSAGE MISSION_ITEM PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM 39 - -typedef struct __mavlink_mission_item_t -{ - float param1; ///< PARAM1, see MAV_CMD enum - float param2; ///< PARAM2, see MAV_CMD enum - float param3; ///< PARAM3, see MAV_CMD enum - float param4; ///< PARAM4, see MAV_CMD enum - float x; ///< PARAM5 / local: x position, global: latitude - float y; ///< PARAM6 / y position: global: longitude - float z; ///< PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - uint16_t seq; ///< Sequence - uint16_t command; ///< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t frame; ///< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - uint8_t current; ///< false:0, true:1 - uint8_t autocontinue; ///< autocontinue to next wp -} mavlink_mission_item_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37 -#define MAVLINK_MSG_ID_39_LEN 37 - -#define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254 -#define MAVLINK_MSG_ID_39_CRC 254 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \ - "MISSION_ITEM", \ - 14, \ - { { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \ - { "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \ - { "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \ - { "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \ - { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \ - { "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \ - { "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \ - } \ -} - - -/** - * @brief Pack a mission_item message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif -} - -/** - * @brief Pack a mission_item message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif -} - -/** - * @brief Encode a mission_item struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) -{ - return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); -} - -/** - * @brief Encode a mission_item struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item) -{ - return mavlink_msg_mission_item_pack_chan(system_id, component_id, chan, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z); -} - -/** - * @brief Send a mission_item message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - * @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - * @param current false:0, true:1 - * @param autocontinue autocontinue to next wp - * @param param1 PARAM1, see MAV_CMD enum - * @param param2 PARAM2, see MAV_CMD enum - * @param param3 PARAM3, see MAV_CMD enum - * @param param4 PARAM4, see MAV_CMD enum - * @param x PARAM5 / local: x position, global: latitude - * @param y PARAM6 / y position: global: longitude - * @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN]; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif -#else - mavlink_mission_item_t packet; - packet.param1 = param1; - packet.param2 = param2; - packet.param3 = param3; - packet.param4 = param4; - packet.x = x; - packet.y = y; - packet.z = z; - packet.seq = seq; - packet.command = command; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - packet.current = current; - packet.autocontinue = autocontinue; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param1); - _mav_put_float(buf, 4, param2); - _mav_put_float(buf, 8, param3); - _mav_put_float(buf, 12, param4); - _mav_put_float(buf, 16, x); - _mav_put_float(buf, 20, y); - _mav_put_float(buf, 24, z); - _mav_put_uint16_t(buf, 28, seq); - _mav_put_uint16_t(buf, 30, command); - _mav_put_uint8_t(buf, 32, target_system); - _mav_put_uint8_t(buf, 33, target_component); - _mav_put_uint8_t(buf, 34, frame); - _mav_put_uint8_t(buf, 35, current); - _mav_put_uint8_t(buf, 36, autocontinue); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif -#else - mavlink_mission_item_t *packet = (mavlink_mission_item_t *)msgbuf; - packet->param1 = param1; - packet->param2 = param2; - packet->param3 = param3; - packet->param4 = param4; - packet->x = x; - packet->y = y; - packet->z = z; - packet->seq = seq; - packet->command = command; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - packet->current = current; - packet->autocontinue = autocontinue; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM UNPACKING - - -/** - * @brief Get field target_system from mission_item message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field target_component from mission_item message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field seq from mission_item message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field frame from mission_item message - * - * @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h - */ -static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 34); -} - -/** - * @brief Get field command from mission_item message - * - * @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs - */ -static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field current from mission_item message - * - * @return false:0, true:1 - */ -static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 35); -} - -/** - * @brief Get field autocontinue from mission_item message - * - * @return autocontinue to next wp - */ -static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 36); -} - -/** - * @brief Get field param1 from mission_item message - * - * @return PARAM1, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param2 from mission_item message - * - * @return PARAM2, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field param3 from mission_item message - * - * @return PARAM3, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field param4 from mission_item message - * - * @return PARAM4, see MAV_CMD enum - */ -static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field x from mission_item message - * - * @return PARAM5 / local: x position, global: latitude - */ -static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field y from mission_item message - * - * @return PARAM6 / y position: global: longitude - */ -static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field z from mission_item message - * - * @return PARAM7 / z position: global: altitude (relative or absolute, depending on frame. - */ -static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a mission_item message into a struct - * - * @param msg The message to decode - * @param mission_item C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_item->param1 = mavlink_msg_mission_item_get_param1(msg); - mission_item->param2 = mavlink_msg_mission_item_get_param2(msg); - mission_item->param3 = mavlink_msg_mission_item_get_param3(msg); - mission_item->param4 = mavlink_msg_mission_item_get_param4(msg); - mission_item->x = mavlink_msg_mission_item_get_x(msg); - mission_item->y = mavlink_msg_mission_item_get_y(msg); - mission_item->z = mavlink_msg_mission_item_get_z(msg); - mission_item->seq = mavlink_msg_mission_item_get_seq(msg); - mission_item->command = mavlink_msg_mission_item_get_command(msg); - mission_item->target_system = mavlink_msg_mission_item_get_target_system(msg); - mission_item->target_component = mavlink_msg_mission_item_get_target_component(msg); - mission_item->frame = mavlink_msg_mission_item_get_frame(msg); - mission_item->current = mavlink_msg_mission_item_get_current(msg); - mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg); -#else - memcpy(mission_item, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h deleted file mode 100644 index 9dfa28043..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h +++ /dev/null @@ -1,209 +0,0 @@ -// MESSAGE MISSION_ITEM_REACHED PACKING - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46 - -typedef struct __mavlink_mission_item_reached_t -{ - uint16_t seq; ///< Sequence -} mavlink_mission_item_reached_t; - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2 -#define MAVLINK_MSG_ID_46_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC 11 -#define MAVLINK_MSG_ID_46_CRC 11 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \ - "MISSION_ITEM_REACHED", \ - 1, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \ - } \ -} - - -/** - * @brief Pack a mission_item_reached message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#else - mavlink_mission_item_reached_t packet; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif -} - -/** - * @brief Pack a mission_item_reached message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#else - mavlink_mission_item_reached_t packet; - packet.seq = seq; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif -} - -/** - * @brief Encode a mission_item_reached struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_item_reached C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) -{ - return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq); -} - -/** - * @brief Encode a mission_item_reached struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_item_reached C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_item_reached_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached) -{ - return mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, chan, msg, mission_item_reached->seq); -} - -/** - * @brief Send a mission_item_reached message - * @param chan MAVLink channel to send the message - * - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_item_reached_send(mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN]; - _mav_put_uint16_t(buf, 0, seq); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif -#else - mavlink_mission_item_reached_t packet; - packet.seq = seq; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_item_reached_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif -#else - mavlink_mission_item_reached_t *packet = (mavlink_mission_item_reached_t *)msgbuf; - packet->seq = seq; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_ITEM_REACHED UNPACKING - - -/** - * @brief Get field seq from mission_item_reached message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_item_reached message into a struct - * - * @param msg The message to decode - * @param mission_item_reached C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message_t* msg, mavlink_mission_item_reached_t* mission_item_reached) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg); -#else - memcpy(mission_item_reached, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h deleted file mode 100644 index 29b0ef6ef..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE MISSION_REQUEST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST 40 - -typedef struct __mavlink_mission_request_t -{ - uint16_t seq; ///< Sequence - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_mission_request_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4 -#define MAVLINK_MSG_ID_40_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230 -#define MAVLINK_MSG_ID_40_CRC 230 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \ - "MISSION_REQUEST", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a mission_request message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#else - mavlink_mission_request_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif -} - -/** - * @brief Pack a mission_request message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#else - mavlink_mission_request_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif -} - -/** - * @brief Encode a mission_request struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) -{ - return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); -} - -/** - * @brief Encode a mission_request struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request) -{ - return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, msg, mission_request->target_system, mission_request->target_component, mission_request->seq); -} - -/** - * @brief Send a mission_request message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif -#else - mavlink_mission_request_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif -#else - mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST UNPACKING - - -/** - * @brief Get field target_system from mission_request message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_request message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_request message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_request message into a struct - * - * @param msg The message to decode - * @param mission_request C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_request->seq = mavlink_msg_mission_request_get_seq(msg); - mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg); - mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg); -#else - memcpy(mission_request, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h deleted file mode 100644 index a275348ac..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE MISSION_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43 - -typedef struct __mavlink_mission_request_list_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_mission_request_list_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2 -#define MAVLINK_MSG_ID_43_LEN 2 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132 -#define MAVLINK_MSG_ID_43_CRC 132 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \ - "MISSION_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a mission_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#else - mavlink_mission_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif -} - -/** - * @brief Pack a mission_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#else - mavlink_mission_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif -} - -/** - * @brief Encode a mission_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) -{ - return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component); -} - -/** - * @brief Encode a mission_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list) -{ - return mavlink_msg_mission_request_list_pack_chan(system_id, component_id, chan, msg, mission_request_list->target_system, mission_request_list->target_component); -} - -/** - * @brief Send a mission_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif -#else - mavlink_mission_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif -#else - mavlink_mission_request_list_t *packet = (mavlink_mission_request_list_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from mission_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a mission_request_list message into a struct - * - * @param msg The message to decode - * @param mission_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_list_decode(const mavlink_message_t* msg, mavlink_mission_request_list_t* mission_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_request_list->target_system = mavlink_msg_mission_request_list_get_target_system(msg); - mission_request_list->target_component = mavlink_msg_mission_request_list_get_target_component(msg); -#else - memcpy(mission_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h deleted file mode 100644 index 79a88dc08..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE MISSION_REQUEST_PARTIAL_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37 - -typedef struct __mavlink_mission_request_partial_list_t -{ - int16_t start_index; ///< Start index, 0 by default - int16_t end_index; ///< End index, -1 by default (-1: send list to end). Else a valid index of the list - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_mission_request_partial_list_t; - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6 -#define MAVLINK_MSG_ID_37_LEN 6 - -#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212 -#define MAVLINK_MSG_ID_37_CRC 212 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \ - "MISSION_REQUEST_PARTIAL_LIST", \ - 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a mission_request_partial_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif -} - -/** - * @brief Pack a mission_request_partial_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif -} - -/** - * @brief Encode a mission_request_partial_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_request_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ - return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); -} - -/** - * @brief Encode a mission_request_partial_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_request_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ - return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index); -} - -/** - * @brief Send a mission_request_partial_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default - * @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif -#else - mavlink_mission_request_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif -#else - mavlink_mission_request_partial_list_t *packet = (mavlink_mission_request_partial_list_t *)msgbuf; - packet->start_index = start_index; - packet->end_index = end_index; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_request_partial_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from mission_request_partial_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start_index from mission_request_partial_list message - * - * @return Start index, 0 by default - */ -static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field end_index from mission_request_partial_list message - * - * @return End index, -1 by default (-1: send list to end). Else a valid index of the list - */ -static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Decode a mission_request_partial_list message into a struct - * - * @param msg The message to decode - * @param mission_request_partial_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_request_partial_list_t* mission_request_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_request_partial_list->start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg); - mission_request_partial_list->end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg); - mission_request_partial_list->target_system = mavlink_msg_mission_request_partial_list_get_target_system(msg); - mission_request_partial_list->target_component = mavlink_msg_mission_request_partial_list_get_target_component(msg); -#else - memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h deleted file mode 100644 index 0c2a3ada4..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE MISSION_SET_CURRENT PACKING - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41 - -typedef struct __mavlink_mission_set_current_t -{ - uint16_t seq; ///< Sequence - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_mission_set_current_t; - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4 -#define MAVLINK_MSG_ID_41_LEN 4 - -#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC 28 -#define MAVLINK_MSG_ID_41_CRC 28 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \ - "MISSION_SET_CURRENT", \ - 3, \ - { { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a mission_set_current message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#else - mavlink_mission_set_current_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif -} - -/** - * @brief Pack a mission_set_current message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_set_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#else - mavlink_mission_set_current_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif -} - -/** - * @brief Encode a mission_set_current struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_set_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) -{ - return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -} - -/** - * @brief Encode a mission_set_current struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_set_current C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_set_current_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current) -{ - return mavlink_msg_mission_set_current_pack_chan(system_id, component_id, chan, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq); -} - -/** - * @brief Send a mission_set_current message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param seq Sequence - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN]; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif -#else - mavlink_mission_set_current_t packet; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_set_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, seq); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif -#else - mavlink_mission_set_current_t *packet = (mavlink_mission_set_current_t *)msgbuf; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_SET_CURRENT UNPACKING - - -/** - * @brief Get field target_system from mission_set_current message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from mission_set_current message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field seq from mission_set_current message - * - * @return Sequence - */ -static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a mission_set_current message into a struct - * - * @param msg The message to decode - * @param mission_set_current C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_t* msg, mavlink_mission_set_current_t* mission_set_current) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_set_current->seq = mavlink_msg_mission_set_current_get_seq(msg); - mission_set_current->target_system = mavlink_msg_mission_set_current_get_target_system(msg); - mission_set_current->target_component = mavlink_msg_mission_set_current_get_target_component(msg); -#else - memcpy(mission_set_current, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h deleted file mode 100644 index 17a5a6bdd..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE MISSION_WRITE_PARTIAL_LIST PACKING - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38 - -typedef struct __mavlink_mission_write_partial_list_t -{ - int16_t start_index; ///< Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - int16_t end_index; ///< End index, equal or greater than start index. - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_mission_write_partial_list_t; - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6 -#define MAVLINK_MSG_ID_38_LEN 6 - -#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9 -#define MAVLINK_MSG_ID_38_CRC 9 - - - -#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \ - "MISSION_WRITE_PARTIAL_LIST", \ - 4, \ - { { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \ - { "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a mission_write_partial_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif -} - -/** - * @brief Pack a mission_write_partial_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif -} - -/** - * @brief Encode a mission_write_partial_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param mission_write_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ - return mavlink_msg_mission_write_partial_list_pack(system_id, component_id, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); -} - -/** - * @brief Encode a mission_write_partial_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param mission_write_partial_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ - return mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, chan, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index); -} - -/** - * @brief Send a mission_write_partial_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - * @param end_index End index, equal or greater than start index. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN]; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif -#else - mavlink_mission_write_partial_list_t packet; - packet.start_index = start_index; - packet.end_index = end_index; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, start_index); - _mav_put_int16_t(buf, 2, end_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif -#else - mavlink_mission_write_partial_list_t *packet = (mavlink_mission_write_partial_list_t *)msgbuf; - packet->start_index = start_index; - packet->end_index = end_index; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MISSION_WRITE_PARTIAL_LIST UNPACKING - - -/** - * @brief Get field target_system from mission_write_partial_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from mission_write_partial_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field start_index from mission_write_partial_list message - * - * @return Start index, 0 by default and smaller / equal to the largest index of the current onboard list. - */ -static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field end_index from mission_write_partial_list message - * - * @return End index, equal or greater than start index. - */ -static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Decode a mission_write_partial_list message into a struct - * - * @param msg The message to decode - * @param mission_write_partial_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_write_partial_list_t* mission_write_partial_list) -{ -#if MAVLINK_NEED_BYTE_SWAP - mission_write_partial_list->start_index = mavlink_msg_mission_write_partial_list_get_start_index(msg); - mission_write_partial_list->end_index = mavlink_msg_mission_write_partial_list_get_end_index(msg); - mission_write_partial_list->target_system = mavlink_msg_mission_write_partial_list_get_target_system(msg); - mission_write_partial_list->target_component = mavlink_msg_mission_write_partial_list_get_target_component(msg); -#else - memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h deleted file mode 100644 index df82704a4..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h +++ /dev/null @@ -1,249 +0,0 @@ -// MESSAGE NAMED_VALUE_FLOAT PACKING - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251 - -typedef struct __mavlink_named_value_float_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - float value; ///< Floating point value - char name[10]; ///< Name of the debug variable -} mavlink_named_value_float_t; - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18 -#define MAVLINK_MSG_ID_251_LEN 18 - -#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC 170 -#define MAVLINK_MSG_ID_251_CRC 170 - -#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10 - -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \ - "NAMED_VALUE_FLOAT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \ - } \ -} - - -/** - * @brief Pack a named_value_float message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#else - mavlink_named_value_float_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif -} - -/** - * @brief Pack a named_value_float message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const char *name,float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#else - mavlink_named_value_float_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif -} - -/** - * @brief Encode a named_value_float struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param named_value_float C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) -{ - return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -} - -/** - * @brief Encode a named_value_float struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param named_value_float C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_float_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float) -{ - return mavlink_msg_named_value_float_pack_chan(system_id, component_id, chan, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value); -} - -/** - * @brief Send a named_value_float message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Floating point value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif -#else - mavlink_named_value_float_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif -#else - mavlink_named_value_float_t *packet = (mavlink_named_value_float_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->value = value; - mav_array_memcpy(packet->name, name, sizeof(char)*10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE NAMED_VALUE_FLOAT UNPACKING - - -/** - * @brief Get field time_boot_ms from named_value_float message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field name from named_value_float message - * - * @return Name of the debug variable - */ -static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 8); -} - -/** - * @brief Get field value from named_value_float message - * - * @return Floating point value - */ -static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Decode a named_value_float message into a struct - * - * @param msg The message to decode - * @param named_value_float C-struct to decode the message contents into - */ -static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float) -{ -#if MAVLINK_NEED_BYTE_SWAP - named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg); - named_value_float->value = mavlink_msg_named_value_float_get_value(msg); - mavlink_msg_named_value_float_get_name(msg, named_value_float->name); -#else - memcpy(named_value_float, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h deleted file mode 100644 index cfdd73d61..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h +++ /dev/null @@ -1,249 +0,0 @@ -// MESSAGE NAMED_VALUE_INT PACKING - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252 - -typedef struct __mavlink_named_value_int_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - int32_t value; ///< Signed integer value - char name[10]; ///< Name of the debug variable -} mavlink_named_value_int_t; - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18 -#define MAVLINK_MSG_ID_252_LEN 18 - -#define MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC 44 -#define MAVLINK_MSG_ID_252_CRC 44 - -#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10 - -#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \ - "NAMED_VALUE_INT", \ - 3, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \ - { "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \ - } \ -} - - -/** - * @brief Pack a named_value_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, const char *name, int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#else - mavlink_named_value_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif -} - -/** - * @brief Pack a named_value_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,const char *name,int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#else - mavlink_named_value_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif -} - -/** - * @brief Encode a named_value_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param named_value_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) -{ - return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -} - -/** - * @brief Encode a named_value_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param named_value_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_named_value_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int) -{ - return mavlink_msg_named_value_int_pack_chan(system_id, component_id, chan, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value); -} - -/** - * @brief Send a named_value_int message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param name Name of the debug variable - * @param value Signed integer value - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif -#else - mavlink_named_value_int_t packet; - packet.time_boot_ms = time_boot_ms; - packet.value = value; - mav_array_memcpy(packet.name, name, sizeof(char)*10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, value); - _mav_put_char_array(buf, 8, name, 10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif -#else - mavlink_named_value_int_t *packet = (mavlink_named_value_int_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->value = value; - mav_array_memcpy(packet->name, name, sizeof(char)*10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE NAMED_VALUE_INT UNPACKING - - -/** - * @brief Get field time_boot_ms from named_value_int message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field name from named_value_int message - * - * @return Name of the debug variable - */ -static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 10, 8); -} - -/** - * @brief Get field value from named_value_int message - * - * @return Signed integer value - */ -static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Decode a named_value_int message into a struct - * - * @param msg The message to decode - * @param named_value_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int) -{ -#if MAVLINK_NEED_BYTE_SWAP - named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg); - named_value_int->value = mavlink_msg_named_value_int_get_value(msg); - mavlink_msg_named_value_int_get_name(msg, named_value_int->name); -#else - memcpy(named_value_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h deleted file mode 100644 index b9a748b22..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h +++ /dev/null @@ -1,377 +0,0 @@ -// MESSAGE NAV_CONTROLLER_OUTPUT PACKING - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62 - -typedef struct __mavlink_nav_controller_output_t -{ - float nav_roll; ///< Current desired roll in degrees - float nav_pitch; ///< Current desired pitch in degrees - float alt_error; ///< Current altitude error in meters - float aspd_error; ///< Current airspeed error in meters/second - float xtrack_error; ///< Current crosstrack error on x-y plane in meters - int16_t nav_bearing; ///< Current desired heading in degrees - int16_t target_bearing; ///< Bearing to current MISSION/target in degrees - uint16_t wp_dist; ///< Distance to active MISSION in meters -} mavlink_nav_controller_output_t; - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26 -#define MAVLINK_MSG_ID_62_LEN 26 - -#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183 -#define MAVLINK_MSG_ID_62_CRC 183 - - - -#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \ - "NAV_CONTROLLER_OUTPUT", \ - 8, \ - { { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \ - { "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \ - { "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \ - { "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \ - { "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \ - { "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \ - { "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \ - { "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \ - } \ -} - - -/** - * @brief Pack a nav_controller_output message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#else - mavlink_nav_controller_output_t packet; - packet.nav_roll = nav_roll; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif -} - -/** - * @brief Pack a nav_controller_output message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#else - mavlink_nav_controller_output_t packet; - packet.nav_roll = nav_roll; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif -} - -/** - * @brief Encode a nav_controller_output struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param nav_controller_output C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) -{ - return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -} - -/** - * @brief Encode a nav_controller_output struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param nav_controller_output C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_nav_controller_output_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output) -{ - return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error); -} - -/** - * @brief Send a nav_controller_output message - * @param chan MAVLink channel to send the message - * - * @param nav_roll Current desired roll in degrees - * @param nav_pitch Current desired pitch in degrees - * @param nav_bearing Current desired heading in degrees - * @param target_bearing Bearing to current MISSION/target in degrees - * @param wp_dist Distance to active MISSION in meters - * @param alt_error Current altitude error in meters - * @param aspd_error Current airspeed error in meters/second - * @param xtrack_error Current crosstrack error on x-y plane in meters - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN]; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif -#else - mavlink_nav_controller_output_t packet; - packet.nav_roll = nav_roll; - packet.nav_pitch = nav_pitch; - packet.alt_error = alt_error; - packet.aspd_error = aspd_error; - packet.xtrack_error = xtrack_error; - packet.nav_bearing = nav_bearing; - packet.target_bearing = target_bearing; - packet.wp_dist = wp_dist; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, nav_roll); - _mav_put_float(buf, 4, nav_pitch); - _mav_put_float(buf, 8, alt_error); - _mav_put_float(buf, 12, aspd_error); - _mav_put_float(buf, 16, xtrack_error); - _mav_put_int16_t(buf, 20, nav_bearing); - _mav_put_int16_t(buf, 22, target_bearing); - _mav_put_uint16_t(buf, 24, wp_dist); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif -#else - mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf; - packet->nav_roll = nav_roll; - packet->nav_pitch = nav_pitch; - packet->alt_error = alt_error; - packet->aspd_error = aspd_error; - packet->xtrack_error = xtrack_error; - packet->nav_bearing = nav_bearing; - packet->target_bearing = target_bearing; - packet->wp_dist = wp_dist; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING - - -/** - * @brief Get field nav_roll from nav_controller_output message - * - * @return Current desired roll in degrees - */ -static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field nav_pitch from nav_controller_output message - * - * @return Current desired pitch in degrees - */ -static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field nav_bearing from nav_controller_output message - * - * @return Current desired heading in degrees - */ -static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field target_bearing from nav_controller_output message - * - * @return Bearing to current MISSION/target in degrees - */ -static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field wp_dist from nav_controller_output message - * - * @return Distance to active MISSION in meters - */ -static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field alt_error from nav_controller_output message - * - * @return Current altitude error in meters - */ -static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field aspd_error from nav_controller_output message - * - * @return Current airspeed error in meters/second - */ -static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field xtrack_error from nav_controller_output message - * - * @return Current crosstrack error on x-y plane in meters - */ -static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a nav_controller_output message into a struct - * - * @param msg The message to decode - * @param nav_controller_output C-struct to decode the message contents into - */ -static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output) -{ -#if MAVLINK_NEED_BYTE_SWAP - nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg); - nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg); - nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg); - nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg); - nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg); - nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg); - nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg); - nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg); -#else - memcpy(nav_controller_output, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h deleted file mode 100644 index 4ee9c452f..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_omnidirectional_flow.h +++ /dev/null @@ -1,322 +0,0 @@ -// MESSAGE OMNIDIRECTIONAL_FLOW PACKING - -#define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW 106 - -typedef struct __mavlink_omnidirectional_flow_t -{ - uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot) - float front_distance_m; ///< Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance - int16_t left[10]; ///< Flow in deci pixels (1 = 0.1 pixel) on left hemisphere - int16_t right[10]; ///< Flow in deci pixels (1 = 0.1 pixel) on right hemisphere - uint8_t sensor_id; ///< Sensor ID - uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality -} mavlink_omnidirectional_flow_t; - -#define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN 54 -#define MAVLINK_MSG_ID_106_LEN 54 - -#define MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC 211 -#define MAVLINK_MSG_ID_106_CRC 211 - -#define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_LEFT_LEN 10 -#define MAVLINK_MSG_OMNIDIRECTIONAL_FLOW_FIELD_RIGHT_LEN 10 - -#define MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW { \ - "OMNIDIRECTIONAL_FLOW", \ - 6, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_omnidirectional_flow_t, time_usec) }, \ - { "front_distance_m", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_omnidirectional_flow_t, front_distance_m) }, \ - { "left", NULL, MAVLINK_TYPE_INT16_T, 10, 12, offsetof(mavlink_omnidirectional_flow_t, left) }, \ - { "right", NULL, MAVLINK_TYPE_INT16_T, 10, 32, offsetof(mavlink_omnidirectional_flow_t, right) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_omnidirectional_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_omnidirectional_flow_t, quality) }, \ - } \ -} - - -/** - * @brief Pack a omnidirectional_flow message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param left Flow in deci pixels (1 = 0.1 pixel) on left hemisphere - * @param right Flow in deci pixels (1 = 0.1 pixel) on right hemisphere - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param front_distance_m Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_omnidirectional_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, front_distance_m); - _mav_put_uint8_t(buf, 52, sensor_id); - _mav_put_uint8_t(buf, 53, quality); - _mav_put_int16_t_array(buf, 12, left, 10); - _mav_put_int16_t_array(buf, 32, right, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#else - mavlink_omnidirectional_flow_t packet; - packet.time_usec = time_usec; - packet.front_distance_m = front_distance_m; - packet.sensor_id = sensor_id; - packet.quality = quality; - mav_array_memcpy(packet.left, left, sizeof(int16_t)*10); - mav_array_memcpy(packet.right, right, sizeof(int16_t)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#endif -} - -/** - * @brief Pack a omnidirectional_flow message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param left Flow in deci pixels (1 = 0.1 pixel) on left hemisphere - * @param right Flow in deci pixels (1 = 0.1 pixel) on right hemisphere - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param front_distance_m Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_omnidirectional_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,const int16_t *left,const int16_t *right,uint8_t quality,float front_distance_m) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, front_distance_m); - _mav_put_uint8_t(buf, 52, sensor_id); - _mav_put_uint8_t(buf, 53, quality); - _mav_put_int16_t_array(buf, 12, left, 10); - _mav_put_int16_t_array(buf, 32, right, 10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#else - mavlink_omnidirectional_flow_t packet; - packet.time_usec = time_usec; - packet.front_distance_m = front_distance_m; - packet.sensor_id = sensor_id; - packet.quality = quality; - mav_array_memcpy(packet.left, left, sizeof(int16_t)*10); - mav_array_memcpy(packet.right, right, sizeof(int16_t)*10); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#endif -} - -/** - * @brief Encode a omnidirectional_flow struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param omnidirectional_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_omnidirectional_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_omnidirectional_flow_t* omnidirectional_flow) -{ - return mavlink_msg_omnidirectional_flow_pack(system_id, component_id, msg, omnidirectional_flow->time_usec, omnidirectional_flow->sensor_id, omnidirectional_flow->left, omnidirectional_flow->right, omnidirectional_flow->quality, omnidirectional_flow->front_distance_m); -} - -/** - * @brief Encode a omnidirectional_flow struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param omnidirectional_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_omnidirectional_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_omnidirectional_flow_t* omnidirectional_flow) -{ - return mavlink_msg_omnidirectional_flow_pack_chan(system_id, component_id, chan, msg, omnidirectional_flow->time_usec, omnidirectional_flow->sensor_id, omnidirectional_flow->left, omnidirectional_flow->right, omnidirectional_flow->quality, omnidirectional_flow->front_distance_m); -} - -/** - * @brief Send a omnidirectional_flow message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param sensor_id Sensor ID - * @param left Flow in deci pixels (1 = 0.1 pixel) on left hemisphere - * @param right Flow in deci pixels (1 = 0.1 pixel) on right hemisphere - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param front_distance_m Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_omnidirectional_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, front_distance_m); - _mav_put_uint8_t(buf, 52, sensor_id); - _mav_put_uint8_t(buf, 53, quality); - _mav_put_int16_t_array(buf, 12, left, 10); - _mav_put_int16_t_array(buf, 32, right, 10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#endif -#else - mavlink_omnidirectional_flow_t packet; - packet.time_usec = time_usec; - packet.front_distance_m = front_distance_m; - packet.sensor_id = sensor_id; - packet.quality = quality; - mav_array_memcpy(packet.left, left, sizeof(int16_t)*10); - mav_array_memcpy(packet.right, right, sizeof(int16_t)*10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_omnidirectional_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, const int16_t *left, const int16_t *right, uint8_t quality, float front_distance_m) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, front_distance_m); - _mav_put_uint8_t(buf, 52, sensor_id); - _mav_put_uint8_t(buf, 53, quality); - _mav_put_int16_t_array(buf, 12, left, 10); - _mav_put_int16_t_array(buf, 32, right, 10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, buf, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#endif -#else - mavlink_omnidirectional_flow_t *packet = (mavlink_omnidirectional_flow_t *)msgbuf; - packet->time_usec = time_usec; - packet->front_distance_m = front_distance_m; - packet->sensor_id = sensor_id; - packet->quality = quality; - mav_array_memcpy(packet->left, left, sizeof(int16_t)*10); - mav_array_memcpy(packet->right, right, sizeof(int16_t)*10); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OMNIDIRECTIONAL_FLOW UNPACKING - - -/** - * @brief Get field time_usec from omnidirectional_flow message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_omnidirectional_flow_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from omnidirectional_flow message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_omnidirectional_flow_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 52); -} - -/** - * @brief Get field left from omnidirectional_flow message - * - * @return Flow in deci pixels (1 = 0.1 pixel) on left hemisphere - */ -static inline uint16_t mavlink_msg_omnidirectional_flow_get_left(const mavlink_message_t* msg, int16_t *left) -{ - return _MAV_RETURN_int16_t_array(msg, left, 10, 12); -} - -/** - * @brief Get field right from omnidirectional_flow message - * - * @return Flow in deci pixels (1 = 0.1 pixel) on right hemisphere - */ -static inline uint16_t mavlink_msg_omnidirectional_flow_get_right(const mavlink_message_t* msg, int16_t *right) -{ - return _MAV_RETURN_int16_t_array(msg, right, 10, 32); -} - -/** - * @brief Get field quality from omnidirectional_flow message - * - * @return Optical flow quality / confidence. 0: bad, 255: maximum quality - */ -static inline uint8_t mavlink_msg_omnidirectional_flow_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 53); -} - -/** - * @brief Get field front_distance_m from omnidirectional_flow message - * - * @return Front distance in meters. Positive value (including zero): distance known. Negative value: Unknown distance - */ -static inline float mavlink_msg_omnidirectional_flow_get_front_distance_m(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Decode a omnidirectional_flow message into a struct - * - * @param msg The message to decode - * @param omnidirectional_flow C-struct to decode the message contents into - */ -static inline void mavlink_msg_omnidirectional_flow_decode(const mavlink_message_t* msg, mavlink_omnidirectional_flow_t* omnidirectional_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP - omnidirectional_flow->time_usec = mavlink_msg_omnidirectional_flow_get_time_usec(msg); - omnidirectional_flow->front_distance_m = mavlink_msg_omnidirectional_flow_get_front_distance_m(msg); - mavlink_msg_omnidirectional_flow_get_left(msg, omnidirectional_flow->left); - mavlink_msg_omnidirectional_flow_get_right(msg, omnidirectional_flow->right); - omnidirectional_flow->sensor_id = mavlink_msg_omnidirectional_flow_get_sensor_id(msg); - omnidirectional_flow->quality = mavlink_msg_omnidirectional_flow_get_quality(msg); -#else - memcpy(omnidirectional_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OMNIDIRECTIONAL_FLOW_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h deleted file mode 100644 index 6a2efc664..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h +++ /dev/null @@ -1,377 +0,0 @@ -// MESSAGE OPTICAL_FLOW PACKING - -#define MAVLINK_MSG_ID_OPTICAL_FLOW 100 - -typedef struct __mavlink_optical_flow_t -{ - uint64_t time_usec; ///< Timestamp (UNIX) - float flow_comp_m_x; ///< Flow in meters in x-sensor direction, angular-speed compensated - float flow_comp_m_y; ///< Flow in meters in y-sensor direction, angular-speed compensated - float ground_distance; ///< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - int16_t flow_x; ///< Flow in pixels * 10 in x-sensor direction (dezi-pixels) - int16_t flow_y; ///< Flow in pixels * 10 in y-sensor direction (dezi-pixels) - uint8_t sensor_id; ///< Sensor ID - uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality -} mavlink_optical_flow_t; - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26 -#define MAVLINK_MSG_ID_100_LEN 26 - -#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175 -#define MAVLINK_MSG_ID_100_CRC 175 - - - -#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \ - "OPTICAL_FLOW", \ - 8, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \ - { "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \ - { "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \ - { "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \ - { "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \ - { "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \ - { "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \ - { "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \ - } \ -} - - -/** - * @brief Pack a optical_flow message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif -} - -/** - * @brief Pack a optical_flow message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif -} - -/** - * @brief Encode a optical_flow struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) -{ - return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); -} - -/** - * @brief Encode a optical_flow struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param optical_flow C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow) -{ - return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance); -} - -/** - * @brief Send a optical_flow message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (UNIX) - * @param sensor_id Sensor ID - * @param flow_x Flow in pixels * 10 in x-sensor direction (dezi-pixels) - * @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels) - * @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated - * @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated - * @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality - * @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif -#else - mavlink_optical_flow_t packet; - packet.time_usec = time_usec; - packet.flow_comp_m_x = flow_comp_m_x; - packet.flow_comp_m_y = flow_comp_m_y; - packet.ground_distance = ground_distance; - packet.flow_x = flow_x; - packet.flow_y = flow_y; - packet.sensor_id = sensor_id; - packet.quality = quality; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_float(buf, 8, flow_comp_m_x); - _mav_put_float(buf, 12, flow_comp_m_y); - _mav_put_float(buf, 16, ground_distance); - _mav_put_int16_t(buf, 20, flow_x); - _mav_put_int16_t(buf, 22, flow_y); - _mav_put_uint8_t(buf, 24, sensor_id); - _mav_put_uint8_t(buf, 25, quality); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif -#else - mavlink_optical_flow_t *packet = (mavlink_optical_flow_t *)msgbuf; - packet->time_usec = time_usec; - packet->flow_comp_m_x = flow_comp_m_x; - packet->flow_comp_m_y = flow_comp_m_y; - packet->ground_distance = ground_distance; - packet->flow_x = flow_x; - packet->flow_y = flow_y; - packet->sensor_id = sensor_id; - packet->quality = quality; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OPTICAL_FLOW UNPACKING - - -/** - * @brief Get field time_usec from optical_flow message - * - * @return Timestamp (UNIX) - */ -static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field sensor_id from optical_flow message - * - * @return Sensor ID - */ -static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field flow_x from optical_flow message - * - * @return Flow in pixels * 10 in x-sensor direction (dezi-pixels) - */ -static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field flow_y from optical_flow message - * - * @return Flow in pixels * 10 in y-sensor direction (dezi-pixels) - */ -static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field flow_comp_m_x from optical_flow message - * - * @return Flow in meters in x-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field flow_comp_m_y from optical_flow message - * - * @return Flow in meters in y-sensor direction, angular-speed compensated - */ -static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field quality from optical_flow message - * - * @return Optical flow quality / confidence. 0: bad, 255: maximum quality - */ -static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field ground_distance from optical_flow message - * - * @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance - */ -static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a optical_flow message into a struct - * - * @param msg The message to decode - * @param optical_flow C-struct to decode the message contents into - */ -static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow) -{ -#if MAVLINK_NEED_BYTE_SWAP - optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg); - optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg); - optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg); - optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg); - optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg); - optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg); - optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg); - optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg); -#else - memcpy(optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OPTICAL_FLOW_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h deleted file mode 100644 index f9466b002..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE PARAM_REQUEST_LIST PACKING - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21 - -typedef struct __mavlink_param_request_list_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_param_request_list_t; - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2 -#define MAVLINK_MSG_ID_21_LEN 2 - -#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC 159 -#define MAVLINK_MSG_ID_21_CRC 159 - - - -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \ - "PARAM_REQUEST_LIST", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a param_request_list message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#else - mavlink_param_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif -} - -/** - * @brief Pack a param_request_list message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_list_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#else - mavlink_param_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif -} - -/** - * @brief Encode a param_request_list struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) -{ - return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component); -} - -/** - * @brief Encode a param_request_list struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_request_list C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list) -{ - return mavlink_msg_param_request_list_pack_chan(system_id, component_id, chan, msg, param_request_list->target_system, param_request_list->target_component); -} - -/** - * @brief Send a param_request_list message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif -#else - mavlink_param_request_list_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif -#else - mavlink_param_request_list_t *packet = (mavlink_param_request_list_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE PARAM_REQUEST_LIST UNPACKING - - -/** - * @brief Get field target_system from param_request_list message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from param_request_list message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a param_request_list message into a struct - * - * @param msg The message to decode - * @param param_request_list C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list) -{ -#if MAVLINK_NEED_BYTE_SWAP - param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg); - param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg); -#else - memcpy(param_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h deleted file mode 100644 index 730cff066..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h +++ /dev/null @@ -1,273 +0,0 @@ -// MESSAGE PARAM_REQUEST_READ PACKING - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20 - -typedef struct __mavlink_param_request_read_t -{ - int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - char param_id[16]; ///< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string -} mavlink_param_request_read_t; - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20 -#define MAVLINK_MSG_ID_20_LEN 20 - -#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214 -#define MAVLINK_MSG_ID_20_CRC 214 - -#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16 - -#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \ - "PARAM_REQUEST_READ", \ - 4, \ - { { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \ - } \ -} - - -/** - * @brief Pack a param_request_read message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#else - mavlink_param_request_read_t packet; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif -} - -/** - * @brief Pack a param_request_read message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_request_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#else - mavlink_param_request_read_t packet; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif -} - -/** - * @brief Encode a param_request_read struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) -{ - return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -} - -/** - * @brief Encode a param_request_read struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_request_read C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_request_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read) -{ - return mavlink_msg_param_request_read_pack_chan(system_id, component_id, chan, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index); -} - -/** - * @brief Send a param_request_read message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN]; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif -#else - mavlink_param_request_read_t packet; - packet.param_index = param_index; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, param_index); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_char_array(buf, 4, param_id, 16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif -#else - mavlink_param_request_read_t *packet = (mavlink_param_request_read_t *)msgbuf; - packet->param_index = param_index; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE PARAM_REQUEST_READ UNPACKING - - -/** - * @brief Get field target_system from param_request_read message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from param_request_read message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field param_id from param_request_read message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 4); -} - -/** - * @brief Get field param_index from param_request_read message - * - * @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored) - */ -static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Decode a param_request_read message into a struct - * - * @param msg The message to decode - * @param param_request_read C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read) -{ -#if MAVLINK_NEED_BYTE_SWAP - param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg); - param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg); - param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg); - mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id); -#else - memcpy(param_request_read, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h deleted file mode 100644 index f669af1a2..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_set.h +++ /dev/null @@ -1,297 +0,0 @@ -// MESSAGE PARAM_SET PACKING - -#define MAVLINK_MSG_ID_PARAM_SET 23 - -typedef struct __mavlink_param_set_t -{ - float param_value; ///< Onboard parameter value - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - char param_id[16]; ///< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - uint8_t param_type; ///< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. -} mavlink_param_set_t; - -#define MAVLINK_MSG_ID_PARAM_SET_LEN 23 -#define MAVLINK_MSG_ID_23_LEN 23 - -#define MAVLINK_MSG_ID_PARAM_SET_CRC 168 -#define MAVLINK_MSG_ID_23_CRC 168 - -#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16 - -#define MAVLINK_MESSAGE_INFO_PARAM_SET { \ - "PARAM_SET", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \ - } \ -} - - -/** - * @brief Pack a param_set message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - packet.target_component = target_component; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_SET; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif -} - -/** - * @brief Pack a param_set message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,const char *param_id,float param_value,uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_SET_LEN); -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - packet.target_component = target_component; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_SET; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif -} - -/** - * @brief Encode a param_set struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set) -{ - return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -} - -/** - * @brief Encode a param_set struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set) -{ - return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type); -} - -/** - * @brief Send a param_set message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_SET_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif -#else - mavlink_param_set_t packet; - packet.param_value = param_value; - packet.target_system = target_system; - packet.target_component = target_component; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param_value); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - _mav_put_uint8_t(buf, 22, param_type); - _mav_put_char_array(buf, 6, param_id, 16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif -#else - mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf; - packet->param_value = param_value; - packet->target_system = target_system; - packet->target_component = target_component; - packet->param_type = param_type; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE PARAM_SET UNPACKING - - -/** - * @brief Get field target_system from param_set message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from param_set message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field param_id from param_set message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 6); -} - -/** - * @brief Get field param_value from param_set message - * - * @return Onboard parameter value - */ -static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param_type from param_set message - * - * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - */ -static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 22); -} - -/** - * @brief Decode a param_set message into a struct - * - * @param msg The message to decode - * @param param_set C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set) -{ -#if MAVLINK_NEED_BYTE_SWAP - param_set->param_value = mavlink_msg_param_set_get_param_value(msg); - param_set->target_system = mavlink_msg_param_set_get_target_system(msg); - param_set->target_component = mavlink_msg_param_set_get_target_component(msg); - mavlink_msg_param_set_get_param_id(msg, param_set->param_id); - param_set->param_type = mavlink_msg_param_set_get_param_type(msg); -#else - memcpy(param_set, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_SET_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h deleted file mode 100644 index c27957913..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_param_value.h +++ /dev/null @@ -1,297 +0,0 @@ -// MESSAGE PARAM_VALUE PACKING - -#define MAVLINK_MSG_ID_PARAM_VALUE 22 - -typedef struct __mavlink_param_value_t -{ - float param_value; ///< Onboard parameter value - uint16_t param_count; ///< Total number of onboard parameters - uint16_t param_index; ///< Index of this onboard parameter - char param_id[16]; ///< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - uint8_t param_type; ///< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. -} mavlink_param_value_t; - -#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25 -#define MAVLINK_MSG_ID_22_LEN 25 - -#define MAVLINK_MSG_ID_PARAM_VALUE_CRC 220 -#define MAVLINK_MSG_ID_22_CRC 220 - -#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16 - -#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \ - "PARAM_VALUE", \ - 5, \ - { { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \ - { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \ - { "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \ - { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \ - { "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \ - } \ -} - - -/** - * @brief Pack a param_value message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint16_t(buf, 4, param_count); - _mav_put_uint16_t(buf, 6, param_index); - _mav_put_uint8_t(buf, 24, param_type); - _mav_put_char_array(buf, 8, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - packet.param_index = param_index; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif -} - -/** - * @brief Pack a param_value message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint16_t(buf, 4, param_count); - _mav_put_uint16_t(buf, 6, param_index); - _mav_put_uint8_t(buf, 24, param_type); - _mav_put_char_array(buf, 8, param_id, 16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - packet.param_index = param_index; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif -} - -/** - * @brief Encode a param_value struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param param_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value) -{ - return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -} - -/** - * @brief Encode a param_value struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param param_value C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_param_value_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_t* param_value) -{ - return mavlink_msg_param_value_pack_chan(system_id, component_id, chan, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index); -} - -/** - * @brief Send a param_value message - * @param chan MAVLink channel to send the message - * - * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - * @param param_value Onboard parameter value - * @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - * @param param_count Total number of onboard parameters - * @param param_index Index of this onboard parameter - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PARAM_VALUE_LEN]; - _mav_put_float(buf, 0, param_value); - _mav_put_uint16_t(buf, 4, param_count); - _mav_put_uint16_t(buf, 6, param_index); - _mav_put_uint8_t(buf, 24, param_type); - _mav_put_char_array(buf, 8, param_id, 16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif -#else - mavlink_param_value_t packet; - packet.param_value = param_value; - packet.param_count = param_count; - packet.param_index = param_index; - packet.param_type = param_type; - mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, param_value); - _mav_put_uint16_t(buf, 4, param_count); - _mav_put_uint16_t(buf, 6, param_index); - _mav_put_uint8_t(buf, 24, param_type); - _mav_put_char_array(buf, 8, param_id, 16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif -#else - mavlink_param_value_t *packet = (mavlink_param_value_t *)msgbuf; - packet->param_value = param_value; - packet->param_count = param_count; - packet->param_index = param_index; - packet->param_type = param_type; - mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE PARAM_VALUE UNPACKING - - -/** - * @brief Get field param_id from param_value message - * - * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string - */ -static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id) -{ - return _MAV_RETURN_char_array(msg, param_id, 16, 8); -} - -/** - * @brief Get field param_value from param_value message - * - * @return Onboard parameter value - */ -static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field param_type from param_value message - * - * @return Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types. - */ -static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field param_count from param_value message - * - * @return Total number of onboard parameters - */ -static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field param_index from param_value message - * - * @return Index of this onboard parameter - */ -static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Decode a param_value message into a struct - * - * @param msg The message to decode - * @param param_value C-struct to decode the message contents into - */ -static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value) -{ -#if MAVLINK_NEED_BYTE_SWAP - param_value->param_value = mavlink_msg_param_value_get_param_value(msg); - param_value->param_count = mavlink_msg_param_value_get_param_count(msg); - param_value->param_index = mavlink_msg_param_value_get_param_index(msg); - mavlink_msg_param_value_get_param_id(msg, param_value->param_id); - param_value->param_type = mavlink_msg_param_value_get_param_type(msg); -#else - memcpy(param_value, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_VALUE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h deleted file mode 100644 index b1501ba1f..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_ping.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE PING PACKING - -#define MAVLINK_MSG_ID_PING 4 - -typedef struct __mavlink_ping_t -{ - uint64_t time_usec; ///< Unix timestamp in microseconds - uint32_t seq; ///< PING sequence - uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system -} mavlink_ping_t; - -#define MAVLINK_MSG_ID_PING_LEN 14 -#define MAVLINK_MSG_ID_4_LEN 14 - -#define MAVLINK_MSG_ID_PING_CRC 237 -#define MAVLINK_MSG_ID_4_CRC 237 - - - -#define MAVLINK_MESSAGE_INFO_PING { \ - "PING", \ - 4, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a ping message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Unix timestamp in microseconds - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PING_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PING; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN); -#endif -} - -/** - * @brief Pack a ping message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Unix timestamp in microseconds - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,uint32_t seq,uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PING_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PING_LEN); -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PING_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PING; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN); -#endif -} - -/** - * @brief Encode a ping struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ping C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping) -{ - return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -} - -/** - * @brief Encode a ping struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param ping C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_ping_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_t* ping) -{ - return mavlink_msg_ping_pack_chan(system_id, component_id, chan, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component); -} - -/** - * @brief Send a ping message - * @param chan MAVLink channel to send the message - * - * @param time_usec Unix timestamp in microseconds - * @param seq PING sequence - * @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - * @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PING_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN); -#endif -#else - mavlink_ping_t packet; - packet.time_usec = time_usec; - packet.seq = seq; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_PING_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_uint8_t(buf, 12, target_system); - _mav_put_uint8_t(buf, 13, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN); -#endif -#else - mavlink_ping_t *packet = (mavlink_ping_t *)msgbuf; - packet->time_usec = time_usec; - packet->seq = seq; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE PING UNPACKING - - -/** - * @brief Get field time_usec from ping message - * - * @return Unix timestamp in microseconds - */ -static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field seq from ping message - * - * @return PING sequence - */ -static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field target_system from ping message - * - * @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system - */ -static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field target_component from ping message - * - * @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system - */ -static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Decode a ping message into a struct - * - * @param msg The message to decode - * @param ping C-struct to decode the message contents into - */ -static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping) -{ -#if MAVLINK_NEED_BYTE_SWAP - ping->time_usec = mavlink_msg_ping_get_time_usec(msg); - ping->seq = mavlink_msg_ping_get_seq(msg); - ping->target_system = mavlink_msg_ping_get_target_system(msg); - ping->target_component = mavlink_msg_ping_get_target_component(msg); -#else - memcpy(ping, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PING_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_power_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_power_status.h deleted file mode 100644 index 1a6259aa3..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_power_status.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE POWER_STATUS PACKING - -#define MAVLINK_MSG_ID_POWER_STATUS 125 - -typedef struct __mavlink_power_status_t -{ - uint16_t Vcc; ///< 5V rail voltage in millivolts - uint16_t Vservo; ///< servo rail voltage in millivolts - uint16_t flags; ///< power supply status flags (see MAV_POWER_STATUS enum) -} mavlink_power_status_t; - -#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6 -#define MAVLINK_MSG_ID_125_LEN 6 - -#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203 -#define MAVLINK_MSG_ID_125_CRC 203 - - - -#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \ - "POWER_STATUS", \ - 3, \ - { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \ - { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \ - } \ -} - - -/** - * @brief Pack a power_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif -} - -/** - * @brief Pack a power_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t Vcc,uint16_t Vservo,uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POWER_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif -} - -/** - * @brief Encode a power_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param power_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_power_status_t* power_status) -{ - return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags); -} - -/** - * @brief Encode a power_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param power_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_power_status_t* power_status) -{ - return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags); -} - -/** - * @brief Send a power_status message - * @param chan MAVLink channel to send the message - * - * @param Vcc 5V rail voltage in millivolts - * @param Vservo servo rail voltage in millivolts - * @param flags power supply status flags (see MAV_POWER_STATUS enum) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif -#else - mavlink_power_status_t packet; - packet.Vcc = Vcc; - packet.Vservo = Vservo; - packet.flags = flags; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, Vcc); - _mav_put_uint16_t(buf, 2, Vservo); - _mav_put_uint16_t(buf, 4, flags); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif -#else - mavlink_power_status_t *packet = (mavlink_power_status_t *)msgbuf; - packet->Vcc = Vcc; - packet->Vservo = Vservo; - packet->flags = flags; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE POWER_STATUS UNPACKING - - -/** - * @brief Get field Vcc from power_status message - * - * @return 5V rail voltage in millivolts - */ -static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field Vservo from power_status message - * - * @return servo rail voltage in millivolts - */ -static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field flags from power_status message - * - * @return power supply status flags (see MAV_POWER_STATUS enum) - */ -static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Decode a power_status message into a struct - * - * @param msg The message to decode - * @param power_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - power_status->Vcc = mavlink_msg_power_status_get_Vcc(msg); - power_status->Vservo = mavlink_msg_power_status_get_Vservo(msg); - power_status->flags = mavlink_msg_power_status_get_flags(msg); -#else - memcpy(power_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POWER_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h deleted file mode 100644 index 5763008fe..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_radio_status.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE RADIO_STATUS PACKING - -#define MAVLINK_MSG_ID_RADIO_STATUS 109 - -typedef struct __mavlink_radio_status_t -{ - uint16_t rxerrors; ///< receive errors - uint16_t fixed; ///< count of error corrected packets - uint8_t rssi; ///< local signal strength - uint8_t remrssi; ///< remote signal strength - uint8_t txbuf; ///< how full the tx buffer is as a percentage - uint8_t noise; ///< background noise level - uint8_t remnoise; ///< remote background noise level -} mavlink_radio_status_t; - -#define MAVLINK_MSG_ID_RADIO_STATUS_LEN 9 -#define MAVLINK_MSG_ID_109_LEN 9 - -#define MAVLINK_MSG_ID_RADIO_STATUS_CRC 185 -#define MAVLINK_MSG_ID_109_CRC 185 - - - -#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \ - "RADIO_STATUS", \ - 7, \ - { { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \ - { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \ - { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \ - { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \ - { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \ - { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \ - } \ -} - - -/** - * @brief Pack a radio_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param rssi local signal strength - * @param remrssi remote signal strength - * @param txbuf how full the tx buffer is as a percentage - * @param noise background noise level - * @param remnoise remote background noise level - * @param rxerrors receive errors - * @param fixed count of error corrected packets - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_radio_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#else - mavlink_radio_status_t packet; - packet.rxerrors = rxerrors; - packet.fixed = fixed; - packet.rssi = rssi; - packet.remrssi = remrssi; - packet.txbuf = txbuf; - packet.noise = noise; - packet.remnoise = remnoise; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif -} - -/** - * @brief Pack a radio_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rssi local signal strength - * @param remrssi remote signal strength - * @param txbuf how full the tx buffer is as a percentage - * @param noise background noise level - * @param remnoise remote background noise level - * @param rxerrors receive errors - * @param fixed count of error corrected packets - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_radio_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#else - mavlink_radio_status_t packet; - packet.rxerrors = rxerrors; - packet.fixed = fixed; - packet.rssi = rssi; - packet.remrssi = remrssi; - packet.txbuf = txbuf; - packet.noise = noise; - packet.remnoise = remnoise; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif -} - -/** - * @brief Encode a radio_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param radio_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_radio_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) -{ - return mavlink_msg_radio_status_pack(system_id, component_id, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); -} - -/** - * @brief Encode a radio_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param radio_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_radio_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status) -{ - return mavlink_msg_radio_status_pack_chan(system_id, component_id, chan, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed); -} - -/** - * @brief Send a radio_status message - * @param chan MAVLink channel to send the message - * - * @param rssi local signal strength - * @param remrssi remote signal strength - * @param txbuf how full the tx buffer is as a percentage - * @param noise background noise level - * @param remnoise remote background noise level - * @param rxerrors receive errors - * @param fixed count of error corrected packets - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_radio_status_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RADIO_STATUS_LEN]; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif -#else - mavlink_radio_status_t packet; - packet.rxerrors = rxerrors; - packet.fixed = fixed; - packet.rssi = rssi; - packet.remrssi = remrssi; - packet.txbuf = txbuf; - packet.noise = noise; - packet.remnoise = remnoise; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RADIO_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_radio_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, rxerrors); - _mav_put_uint16_t(buf, 2, fixed); - _mav_put_uint8_t(buf, 4, rssi); - _mav_put_uint8_t(buf, 5, remrssi); - _mav_put_uint8_t(buf, 6, txbuf); - _mav_put_uint8_t(buf, 7, noise); - _mav_put_uint8_t(buf, 8, remnoise); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif -#else - mavlink_radio_status_t *packet = (mavlink_radio_status_t *)msgbuf; - packet->rxerrors = rxerrors; - packet->fixed = fixed; - packet->rssi = rssi; - packet->remrssi = remrssi; - packet->txbuf = txbuf; - packet->noise = noise; - packet->remnoise = remnoise; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RADIO_STATUS UNPACKING - - -/** - * @brief Get field rssi from radio_status message - * - * @return local signal strength - */ -static inline uint8_t mavlink_msg_radio_status_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field remrssi from radio_status message - * - * @return remote signal strength - */ -static inline uint8_t mavlink_msg_radio_status_get_remrssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field txbuf from radio_status message - * - * @return how full the tx buffer is as a percentage - */ -static inline uint8_t mavlink_msg_radio_status_get_txbuf(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field noise from radio_status message - * - * @return background noise level - */ -static inline uint8_t mavlink_msg_radio_status_get_noise(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field remnoise from radio_status message - * - * @return remote background noise level - */ -static inline uint8_t mavlink_msg_radio_status_get_remnoise(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field rxerrors from radio_status message - * - * @return receive errors - */ -static inline uint16_t mavlink_msg_radio_status_get_rxerrors(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field fixed from radio_status message - * - * @return count of error corrected packets - */ -static inline uint16_t mavlink_msg_radio_status_get_fixed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a radio_status message into a struct - * - * @param msg The message to decode - * @param radio_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_radio_status_decode(const mavlink_message_t* msg, mavlink_radio_status_t* radio_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - radio_status->rxerrors = mavlink_msg_radio_status_get_rxerrors(msg); - radio_status->fixed = mavlink_msg_radio_status_get_fixed(msg); - radio_status->rssi = mavlink_msg_radio_status_get_rssi(msg); - radio_status->remrssi = mavlink_msg_radio_status_get_remrssi(msg); - radio_status->txbuf = mavlink_msg_radio_status_get_txbuf(msg); - radio_status->noise = mavlink_msg_radio_status_get_noise(msg); - radio_status->remnoise = mavlink_msg_radio_status_get_remnoise(msg); -#else - memcpy(radio_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RADIO_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h deleted file mode 100644 index a98e8ce72..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h +++ /dev/null @@ -1,425 +0,0 @@ -// MESSAGE RAW_IMU PACKING - -#define MAVLINK_MSG_ID_RAW_IMU 27 - -typedef struct __mavlink_raw_imu_t -{ - uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - int16_t xacc; ///< X acceleration (raw) - int16_t yacc; ///< Y acceleration (raw) - int16_t zacc; ///< Z acceleration (raw) - int16_t xgyro; ///< Angular speed around X axis (raw) - int16_t ygyro; ///< Angular speed around Y axis (raw) - int16_t zgyro; ///< Angular speed around Z axis (raw) - int16_t xmag; ///< X Magnetic field (raw) - int16_t ymag; ///< Y Magnetic field (raw) - int16_t zmag; ///< Z Magnetic field (raw) -} mavlink_raw_imu_t; - -#define MAVLINK_MSG_ID_RAW_IMU_LEN 26 -#define MAVLINK_MSG_ID_27_LEN 26 - -#define MAVLINK_MSG_ID_RAW_IMU_CRC 144 -#define MAVLINK_MSG_ID_27_CRC 144 - - - -#define MAVLINK_MESSAGE_INFO_RAW_IMU { \ - "RAW_IMU", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \ - } \ -} - - -/** - * @brief Pack a raw_imu message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_IMU; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif -} - -/** - * @brief Pack a raw_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_IMU; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif -} - -/** - * @brief Encode a raw_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) -{ - return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); -} - -/** - * @brief Encode a raw_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu) -{ - return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag); -} - -/** - * @brief Send a raw_imu message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param xacc X acceleration (raw) - * @param yacc Y acceleration (raw) - * @param zacc Z acceleration (raw) - * @param xgyro Angular speed around X axis (raw) - * @param ygyro Angular speed around Y axis (raw) - * @param zgyro Angular speed around Z axis (raw) - * @param xmag X Magnetic field (raw) - * @param ymag Y Magnetic field (raw) - * @param zmag Z Magnetic field (raw) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_IMU_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif -#else - mavlink_raw_imu_t packet; - packet.time_usec = time_usec; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, xacc); - _mav_put_int16_t(buf, 10, yacc); - _mav_put_int16_t(buf, 12, zacc); - _mav_put_int16_t(buf, 14, xgyro); - _mav_put_int16_t(buf, 16, ygyro); - _mav_put_int16_t(buf, 18, zgyro); - _mav_put_int16_t(buf, 20, xmag); - _mav_put_int16_t(buf, 22, ymag); - _mav_put_int16_t(buf, 24, zmag); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif -#else - mavlink_raw_imu_t *packet = (mavlink_raw_imu_t *)msgbuf; - packet->time_usec = time_usec; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RAW_IMU UNPACKING - - -/** - * @brief Get field time_usec from raw_imu message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field xacc from raw_imu message - * - * @return X acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field yacc from raw_imu message - * - * @return Y acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field zacc from raw_imu message - * - * @return Z acceleration (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field xgyro from raw_imu message - * - * @return Angular speed around X axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field ygyro from raw_imu message - * - * @return Angular speed around Y axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field zgyro from raw_imu message - * - * @return Angular speed around Z axis (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field xmag from raw_imu message - * - * @return X Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field ymag from raw_imu message - * - * @return Y Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field zmag from raw_imu message - * - * @return Z Magnetic field (raw) - */ -static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Decode a raw_imu message into a struct - * - * @param msg The message to decode - * @param raw_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP - raw_imu->time_usec = mavlink_msg_raw_imu_get_time_usec(msg); - raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg); - raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg); - raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg); - raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg); - raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg); - raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg); - raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg); - raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg); - raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg); -#else - memcpy(raw_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_IMU_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h deleted file mode 100644 index 6bd37fcae..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE RAW_PRESSURE PACKING - -#define MAVLINK_MSG_ID_RAW_PRESSURE 28 - -typedef struct __mavlink_raw_pressure_t -{ - uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot) - int16_t press_abs; ///< Absolute pressure (raw) - int16_t press_diff1; ///< Differential pressure 1 (raw) - int16_t press_diff2; ///< Differential pressure 2 (raw) - int16_t temperature; ///< Raw Temperature measurement (raw) -} mavlink_raw_pressure_t; - -#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16 -#define MAVLINK_MSG_ID_28_LEN 16 - -#define MAVLINK_MSG_ID_RAW_PRESSURE_CRC 67 -#define MAVLINK_MSG_ID_28_CRC 67 - - - -#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \ - "RAW_PRESSURE", \ - 5, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \ - { "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \ - { "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \ - { "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \ - } \ -} - - -/** - * @brief Pack a raw_pressure message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw) - * @param press_diff2 Differential pressure 2 (raw) - * @param temperature Raw Temperature measurement (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, press_abs); - _mav_put_int16_t(buf, 10, press_diff1); - _mav_put_int16_t(buf, 12, press_diff2); - _mav_put_int16_t(buf, 14, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif -} - -/** - * @brief Pack a raw_pressure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw) - * @param press_diff2 Differential pressure 2 (raw) - * @param temperature Raw Temperature measurement (raw) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, press_abs); - _mav_put_int16_t(buf, 10, press_diff1); - _mav_put_int16_t(buf, 12, press_diff2); - _mav_put_int16_t(buf, 14, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif -} - -/** - * @brief Encode a raw_pressure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) -{ - return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -} - -/** - * @brief Encode a raw_pressure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure) -{ - return mavlink_msg_raw_pressure_pack_chan(system_id, component_id, chan, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature); -} - -/** - * @brief Send a raw_pressure message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param press_abs Absolute pressure (raw) - * @param press_diff1 Differential pressure 1 (raw) - * @param press_diff2 Differential pressure 2 (raw) - * @param temperature Raw Temperature measurement (raw) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_PRESSURE_LEN]; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, press_abs); - _mav_put_int16_t(buf, 10, press_diff1); - _mav_put_int16_t(buf, 12, press_diff2); - _mav_put_int16_t(buf, 14, temperature); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif -#else - mavlink_raw_pressure_t packet; - packet.time_usec = time_usec; - packet.press_abs = press_abs; - packet.press_diff1 = press_diff1; - packet.press_diff2 = press_diff2; - packet.temperature = temperature; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_usec); - _mav_put_int16_t(buf, 8, press_abs); - _mav_put_int16_t(buf, 10, press_diff1); - _mav_put_int16_t(buf, 12, press_diff2); - _mav_put_int16_t(buf, 14, temperature); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif -#else - mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf; - packet->time_usec = time_usec; - packet->press_abs = press_abs; - packet->press_diff1 = press_diff1; - packet->press_diff2 = press_diff2; - packet->temperature = temperature; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RAW_PRESSURE UNPACKING - - -/** - * @brief Get field time_usec from raw_pressure message - * - * @return Timestamp (microseconds since UNIX epoch or microseconds since system boot) - */ -static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field press_abs from raw_pressure message - * - * @return Absolute pressure (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field press_diff1 from raw_pressure message - * - * @return Differential pressure 1 (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field press_diff2 from raw_pressure message - * - * @return Differential pressure 2 (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field temperature from raw_pressure message - * - * @return Raw Temperature measurement (raw) - */ -static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Decode a raw_pressure message into a struct - * - * @param msg The message to decode - * @param raw_pressure C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP - raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg); - raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg); - raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg); - raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg); - raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg); -#else - memcpy(raw_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_PRESSURE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h deleted file mode 100644 index 479af122f..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels.h +++ /dev/null @@ -1,689 +0,0 @@ -// MESSAGE RC_CHANNELS PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS 65 - -typedef struct __mavlink_rc_channels_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - uint16_t chan1_raw; ///< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan9_raw; ///< RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan10_raw; ///< RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan11_raw; ///< RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan12_raw; ///< RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan13_raw; ///< RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan14_raw; ///< RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan15_raw; ///< RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan16_raw; ///< RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan17_raw; ///< RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan18_raw; ///< RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint8_t chancount; ///< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. -} mavlink_rc_channels_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42 -#define MAVLINK_MSG_ID_65_LEN 42 - -#define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118 -#define MAVLINK_MSG_ID_65_CRC 118 - - - -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \ - "RC_CHANNELS", \ - 21, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \ - { "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \ - { "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \ - { "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \ - { "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \ - { "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \ - { "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \ - { "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \ - { "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \ - { "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \ - { "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \ - { "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \ - } \ -} - - -/** - * @brief Pack a rc_channels message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif -} - -/** - * @brief Pack a rc_channels message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t chancount,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif -} - -/** - * @brief Encode a rc_channels struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) -{ - return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -} - -/** - * @brief Encode a rc_channels struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels) -{ - return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi); -} - -/** - * @brief Send a rc_channels message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif -#else - mavlink_rc_channels_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.chan9_raw = chan9_raw; - packet.chan10_raw = chan10_raw; - packet.chan11_raw = chan11_raw; - packet.chan12_raw = chan12_raw; - packet.chan13_raw = chan13_raw; - packet.chan14_raw = chan14_raw; - packet.chan15_raw = chan15_raw; - packet.chan16_raw = chan16_raw; - packet.chan17_raw = chan17_raw; - packet.chan18_raw = chan18_raw; - packet.chancount = chancount; - packet.rssi = rssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint16_t(buf, 20, chan9_raw); - _mav_put_uint16_t(buf, 22, chan10_raw); - _mav_put_uint16_t(buf, 24, chan11_raw); - _mav_put_uint16_t(buf, 26, chan12_raw); - _mav_put_uint16_t(buf, 28, chan13_raw); - _mav_put_uint16_t(buf, 30, chan14_raw); - _mav_put_uint16_t(buf, 32, chan15_raw); - _mav_put_uint16_t(buf, 34, chan16_raw); - _mav_put_uint16_t(buf, 36, chan17_raw); - _mav_put_uint16_t(buf, 38, chan18_raw); - _mav_put_uint8_t(buf, 40, chancount); - _mav_put_uint8_t(buf, 41, rssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif -#else - mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->chan9_raw = chan9_raw; - packet->chan10_raw = chan10_raw; - packet->chan11_raw = chan11_raw; - packet->chan12_raw = chan12_raw; - packet->chan13_raw = chan13_raw; - packet->chan14_raw = chan14_raw; - packet->chan15_raw = chan15_raw; - packet->chan16_raw = chan16_raw; - packet->chan17_raw = chan17_raw; - packet->chan18_raw = chan18_raw; - packet->chancount = chancount; - packet->rssi = rssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field chancount from rc_channels message - * - * @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available. - */ -static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 40); -} - -/** - * @brief Get field chan1_raw from rc_channels message - * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan2_raw from rc_channels message - * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan3_raw from rc_channels message - * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan4_raw from rc_channels message - * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan5_raw from rc_channels message - * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan6_raw from rc_channels message - * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan7_raw from rc_channels message - * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan8_raw from rc_channels message - * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field chan9_raw from rc_channels message - * - * @return RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field chan10_raw from rc_channels message - * - * @return RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field chan11_raw from rc_channels message - * - * @return RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field chan12_raw from rc_channels message - * - * @return RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field chan13_raw from rc_channels message - * - * @return RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Get field chan14_raw from rc_channels message - * - * @return RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 30); -} - -/** - * @brief Get field chan15_raw from rc_channels message - * - * @return RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 32); -} - -/** - * @brief Get field chan16_raw from rc_channels message - * - * @return RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 34); -} - -/** - * @brief Get field chan17_raw from rc_channels message - * - * @return RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 36); -} - -/** - * @brief Get field chan18_raw from rc_channels message - * - * @return RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 38); -} - -/** - * @brief Get field rssi from rc_channels message - * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 41); -} - -/** - * @brief Decode a rc_channels message into a struct - * - * @param msg The message to decode - * @param rc_channels C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_decode(const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels) -{ -#if MAVLINK_NEED_BYTE_SWAP - rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg); - rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg); - rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg); - rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg); - rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg); - rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg); - rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg); - rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg); - rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg); - rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg); - rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg); - rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg); - rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg); - rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg); - rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg); - rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg); - rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg); - rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg); - rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg); - rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg); - rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg); -#else - memcpy(rc_channels, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h deleted file mode 100644 index 15d4c6f95..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h +++ /dev/null @@ -1,425 +0,0 @@ -// MESSAGE RC_CHANNELS_OVERRIDE PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70 - -typedef struct __mavlink_rc_channels_override_t -{ - uint16_t chan1_raw; ///< RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_rc_channels_override_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18 -#define MAVLINK_MSG_ID_70_LEN 18 - -#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124 -#define MAVLINK_MSG_ID_70_CRC 124 - - - -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \ - "RC_CHANNELS_OVERRIDE", \ - 10, \ - { { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a rc_channels_override message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#else - mavlink_rc_channels_override_t packet; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif -} - -/** - * @brief Pack a rc_channels_override message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_override_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#else - mavlink_rc_channels_override_t packet; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif -} - -/** - * @brief Encode a rc_channels_override struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_override C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) -{ - return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); -} - -/** - * @brief Encode a rc_channels_override struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_override C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_override_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override) -{ - return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw); -} - -/** - * @brief Send a rc_channels_override message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN]; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif -#else - mavlink_rc_channels_override_t packet; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, chan1_raw); - _mav_put_uint16_t(buf, 2, chan2_raw); - _mav_put_uint16_t(buf, 4, chan3_raw); - _mav_put_uint16_t(buf, 6, chan4_raw); - _mav_put_uint16_t(buf, 8, chan5_raw); - _mav_put_uint16_t(buf, 10, chan6_raw); - _mav_put_uint16_t(buf, 12, chan7_raw); - _mav_put_uint16_t(buf, 14, chan8_raw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif -#else - mavlink_rc_channels_override_t *packet = (mavlink_rc_channels_override_t *)msgbuf; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING - - -/** - * @brief Get field target_system from rc_channels_override message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from rc_channels_override message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field chan1_raw from rc_channels_override message - * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field chan2_raw from rc_channels_override message - * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field chan3_raw from rc_channels_override message - * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan4_raw from rc_channels_override message - * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan5_raw from rc_channels_override message - * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan6_raw from rc_channels_override message - * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan7_raw from rc_channels_override message - * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan8_raw from rc_channels_override message - * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field. - */ -static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Decode a rc_channels_override message into a struct - * - * @param msg The message to decode - * @param rc_channels_override C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override) -{ -#if MAVLINK_NEED_BYTE_SWAP - rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg); - rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg); - rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg); - rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg); - rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg); - rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg); - rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg); - rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg); - rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg); - rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg); -#else - memcpy(rc_channels_override, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h deleted file mode 100644 index d75a5934a..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h +++ /dev/null @@ -1,449 +0,0 @@ -// MESSAGE RC_CHANNELS_RAW PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35 - -typedef struct __mavlink_rc_channels_raw_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - uint16_t chan1_raw; ///< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. -} mavlink_rc_channels_raw_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22 -#define MAVLINK_MSG_ID_35_LEN 22 - -#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244 -#define MAVLINK_MSG_ID_35_CRC 244 - - - -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \ - "RC_CHANNELS_RAW", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \ - { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \ - { "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \ - { "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \ - { "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \ - { "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \ - { "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \ - { "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \ - { "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \ - } \ -} - - -/** - * @brief Pack a rc_channels_raw message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#else - mavlink_rc_channels_raw_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif -} - -/** - * @brief Pack a rc_channels_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t port,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#else - mavlink_rc_channels_raw_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif -} - -/** - * @brief Encode a rc_channels_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ - return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -} - -/** - * @brief Encode a rc_channels_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw) -{ - return mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, chan, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi); -} - -/** - * @brief Send a rc_channels_raw message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif -#else - mavlink_rc_channels_raw_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_raw = chan1_raw; - packet.chan2_raw = chan2_raw; - packet.chan3_raw = chan3_raw; - packet.chan4_raw = chan4_raw; - packet.chan5_raw = chan5_raw; - packet.chan6_raw = chan6_raw; - packet.chan7_raw = chan7_raw; - packet.chan8_raw = chan8_raw; - packet.port = port; - packet.rssi = rssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_uint16_t(buf, 4, chan1_raw); - _mav_put_uint16_t(buf, 6, chan2_raw); - _mav_put_uint16_t(buf, 8, chan3_raw); - _mav_put_uint16_t(buf, 10, chan4_raw); - _mav_put_uint16_t(buf, 12, chan5_raw); - _mav_put_uint16_t(buf, 14, chan6_raw); - _mav_put_uint16_t(buf, 16, chan7_raw); - _mav_put_uint16_t(buf, 18, chan8_raw); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif -#else - mavlink_rc_channels_raw_t *packet = (mavlink_rc_channels_raw_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_raw = chan1_raw; - packet->chan2_raw = chan2_raw; - packet->chan3_raw = chan3_raw; - packet->chan4_raw = chan4_raw; - packet->chan5_raw = chan5_raw; - packet->chan6_raw = chan6_raw; - packet->chan7_raw = chan7_raw; - packet->chan8_raw = chan8_raw; - packet->port = port; - packet->rssi = rssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_RAW UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels_raw message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from rc_channels_raw message - * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - */ -static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field chan1_raw from rc_channels_raw message - * - * @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field chan2_raw from rc_channels_raw message - * - * @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field chan3_raw from rc_channels_raw message - * - * @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field chan4_raw from rc_channels_raw message - * - * @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field chan5_raw from rc_channels_raw message - * - * @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field chan6_raw from rc_channels_raw message - * - * @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field chan7_raw from rc_channels_raw message - * - * @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field chan8_raw from rc_channels_raw message - * - * @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused. - */ -static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field rssi from rc_channels_raw message - * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a rc_channels_raw message into a struct - * - * @param msg The message to decode - * @param rc_channels_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP - rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg); - rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg); - rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg); - rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg); - rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg); - rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg); - rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg); - rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg); - rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg); - rc_channels_raw->port = mavlink_msg_rc_channels_raw_get_port(msg); - rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg); -#else - memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h deleted file mode 100644 index f400f987d..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h +++ /dev/null @@ -1,449 +0,0 @@ -// MESSAGE RC_CHANNELS_SCALED PACKING - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34 - -typedef struct __mavlink_rc_channels_scaled_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - int16_t chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. -} mavlink_rc_channels_scaled_t; - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22 -#define MAVLINK_MSG_ID_34_LEN 22 - -#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237 -#define MAVLINK_MSG_ID_34_CRC 237 - - - -#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \ - "RC_CHANNELS_SCALED", \ - 11, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \ - { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \ - { "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \ - { "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \ - { "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \ - { "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \ - { "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \ - { "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \ - { "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \ - { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \ - } \ -} - - -/** - * @brief Pack a rc_channels_scaled message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, chan1_scaled); - _mav_put_int16_t(buf, 6, chan2_scaled); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#else - mavlink_rc_channels_scaled_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif -} - -/** - * @brief Pack a rc_channels_scaled message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t port,int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, chan1_scaled); - _mav_put_int16_t(buf, 6, chan2_scaled); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#else - mavlink_rc_channels_scaled_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif -} - -/** - * @brief Encode a rc_channels_scaled struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param rc_channels_scaled C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ - return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -} - -/** - * @brief Encode a rc_channels_scaled struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rc_channels_scaled C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_rc_channels_scaled_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ - return mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, chan, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi); -} - -/** - * @brief Send a rc_channels_scaled message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - * @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - * @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, chan1_scaled); - _mav_put_int16_t(buf, 6, chan2_scaled); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif -#else - mavlink_rc_channels_scaled_t packet; - packet.time_boot_ms = time_boot_ms; - packet.chan1_scaled = chan1_scaled; - packet.chan2_scaled = chan2_scaled; - packet.chan3_scaled = chan3_scaled; - packet.chan4_scaled = chan4_scaled; - packet.chan5_scaled = chan5_scaled; - packet.chan6_scaled = chan6_scaled; - packet.chan7_scaled = chan7_scaled; - packet.chan8_scaled = chan8_scaled; - packet.port = port; - packet.rssi = rssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, chan1_scaled); - _mav_put_int16_t(buf, 6, chan2_scaled); - _mav_put_int16_t(buf, 8, chan3_scaled); - _mav_put_int16_t(buf, 10, chan4_scaled); - _mav_put_int16_t(buf, 12, chan5_scaled); - _mav_put_int16_t(buf, 14, chan6_scaled); - _mav_put_int16_t(buf, 16, chan7_scaled); - _mav_put_int16_t(buf, 18, chan8_scaled); - _mav_put_uint8_t(buf, 20, port); - _mav_put_uint8_t(buf, 21, rssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif -#else - mavlink_rc_channels_scaled_t *packet = (mavlink_rc_channels_scaled_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->chan1_scaled = chan1_scaled; - packet->chan2_scaled = chan2_scaled; - packet->chan3_scaled = chan3_scaled; - packet->chan4_scaled = chan4_scaled; - packet->chan5_scaled = chan5_scaled; - packet->chan6_scaled = chan6_scaled; - packet->chan7_scaled = chan7_scaled; - packet->chan8_scaled = chan8_scaled; - packet->port = port; - packet->rssi = rssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RC_CHANNELS_SCALED UNPACKING - - -/** - * @brief Get field time_boot_ms from rc_channels_scaled message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from rc_channels_scaled message - * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos. - */ -static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field chan1_scaled from rc_channels_scaled message - * - * @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field chan2_scaled from rc_channels_scaled message - * - * @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field chan3_scaled from rc_channels_scaled message - * - * @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field chan4_scaled from rc_channels_scaled message - * - * @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field chan5_scaled from rc_channels_scaled message - * - * @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field chan6_scaled from rc_channels_scaled message - * - * @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field chan7_scaled from rc_channels_scaled message - * - * @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field chan8_scaled from rc_channels_scaled message - * - * @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX. - */ -static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field rssi from rc_channels_scaled message - * - * @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown. - */ -static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 21); -} - -/** - * @brief Decode a rc_channels_scaled message into a struct - * - * @param msg The message to decode - * @param rc_channels_scaled C-struct to decode the message contents into - */ -static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled) -{ -#if MAVLINK_NEED_BYTE_SWAP - rc_channels_scaled->time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg); - rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg); - rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg); - rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg); - rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg); - rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg); - rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg); - rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg); - rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg); - rc_channels_scaled->port = mavlink_msg_rc_channels_scaled_get_port(msg); - rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg); -#else - memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h deleted file mode 100644 index 2ebcc54da..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE REQUEST_DATA_STREAM PACKING - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66 - -typedef struct __mavlink_request_data_stream_t -{ - uint16_t req_message_rate; ///< The requested interval between two messages of this type - uint8_t target_system; ///< The target requested to send the message stream. - uint8_t target_component; ///< The target requested to send the message stream. - uint8_t req_stream_id; ///< The ID of the requested data stream - uint8_t start_stop; ///< 1 to start sending, 0 to stop sending. -} mavlink_request_data_stream_t; - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6 -#define MAVLINK_MSG_ID_66_LEN 6 - -#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC 148 -#define MAVLINK_MSG_ID_66_CRC 148 - - - -#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \ - "REQUEST_DATA_STREAM", \ - 5, \ - { { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \ - { "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \ - { "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \ - } \ -} - - -/** - * @brief Pack a request_data_stream message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested interval between two messages of this type - * @param start_stop 1 to start sending, 0 to stop sending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, req_message_rate); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, req_stream_id); - _mav_put_uint8_t(buf, 5, start_stop); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif -} - -/** - * @brief Pack a request_data_stream message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested interval between two messages of this type - * @param start_stop 1 to start sending, 0 to stop sending. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_request_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t req_stream_id,uint16_t req_message_rate,uint8_t start_stop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, req_message_rate); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, req_stream_id); - _mav_put_uint8_t(buf, 5, start_stop); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif -} - -/** - * @brief Encode a request_data_stream struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param request_data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) -{ - return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -} - -/** - * @brief Encode a request_data_stream struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param request_data_stream C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_request_data_stream_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream) -{ - return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop); -} - -/** - * @brief Send a request_data_stream message - * @param chan MAVLink channel to send the message - * - * @param target_system The target requested to send the message stream. - * @param target_component The target requested to send the message stream. - * @param req_stream_id The ID of the requested data stream - * @param req_message_rate The requested interval between two messages of this type - * @param start_stop 1 to start sending, 0 to stop sending. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN]; - _mav_put_uint16_t(buf, 0, req_message_rate); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, req_stream_id); - _mav_put_uint8_t(buf, 5, start_stop); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif -#else - mavlink_request_data_stream_t packet; - packet.req_message_rate = req_message_rate; - packet.target_system = target_system; - packet.target_component = target_component; - packet.req_stream_id = req_stream_id; - packet.start_stop = start_stop; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, req_message_rate); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, req_stream_id); - _mav_put_uint8_t(buf, 5, start_stop); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif -#else - mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf; - packet->req_message_rate = req_message_rate; - packet->target_system = target_system; - packet->target_component = target_component; - packet->req_stream_id = req_stream_id; - packet->start_stop = start_stop; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE REQUEST_DATA_STREAM UNPACKING - - -/** - * @brief Get field target_system from request_data_stream message - * - * @return The target requested to send the message stream. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from request_data_stream message - * - * @return The target requested to send the message stream. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field req_stream_id from request_data_stream message - * - * @return The ID of the requested data stream - */ -static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field req_message_rate from request_data_stream message - * - * @return The requested interval between two messages of this type - */ -static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field start_stop from request_data_stream message - * - * @return 1 to start sending, 0 to stop sending. - */ -static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Decode a request_data_stream message into a struct - * - * @param msg The message to decode - * @param request_data_stream C-struct to decode the message contents into - */ -static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream) -{ -#if MAVLINK_NEED_BYTE_SWAP - request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg); - request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg); - request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg); - request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg); - request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg); -#else - memcpy(request_data_stream, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h deleted file mode 100644 index 131b756b6..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT PACKING - -#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT 80 - -typedef struct __mavlink_roll_pitch_yaw_rates_thrust_setpoint_t -{ - uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot - float roll_rate; ///< Desired roll rate in radians per second - float pitch_rate; ///< Desired pitch rate in radians per second - float yaw_rate; ///< Desired yaw rate in radians per second - float thrust; ///< Collective thrust, normalized to 0 .. 1 -} mavlink_roll_pitch_yaw_rates_thrust_setpoint_t; - -#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN 20 -#define MAVLINK_MSG_ID_80_LEN 20 - -#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC 127 -#define MAVLINK_MSG_ID_80_CRC 127 - - - -#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT { \ - "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, time_boot_ms) }, \ - { "roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, roll_rate) }, \ - { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, pitch_rate) }, \ - { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, yaw_rate) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_rates_thrust_setpoint_t, thrust) }, \ - } \ -} - - -/** - * @brief Pack a roll_pitch_yaw_rates_thrust_setpoint message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll_rate Desired roll rate in radians per second - * @param pitch_rate Desired pitch rate in radians per second - * @param yaw_rate Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll_rate); - _mav_put_float(buf, 8, pitch_rate); - _mav_put_float(buf, 12, yaw_rate); - _mav_put_float(buf, 16, thrust); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#else - mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - packet.thrust = thrust; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#endif -} - -/** - * @brief Pack a roll_pitch_yaw_rates_thrust_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll_rate Desired roll rate in radians per second - * @param pitch_rate Desired pitch rate in radians per second - * @param yaw_rate Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float roll_rate,float pitch_rate,float yaw_rate,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll_rate); - _mav_put_float(buf, 8, pitch_rate); - _mav_put_float(buf, 12, yaw_rate); - _mav_put_float(buf, 16, thrust); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#else - mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - packet.thrust = thrust; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#endif -} - -/** - * @brief Encode a roll_pitch_yaw_rates_thrust_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param roll_pitch_yaw_rates_thrust_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint) -{ - return mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms, roll_pitch_yaw_rates_thrust_setpoint->roll_rate, roll_pitch_yaw_rates_thrust_setpoint->pitch_rate, roll_pitch_yaw_rates_thrust_setpoint->yaw_rate, roll_pitch_yaw_rates_thrust_setpoint->thrust); -} - -/** - * @brief Encode a roll_pitch_yaw_rates_thrust_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param roll_pitch_yaw_rates_thrust_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint) -{ - return mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_pack_chan(system_id, component_id, chan, msg, roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms, roll_pitch_yaw_rates_thrust_setpoint->roll_rate, roll_pitch_yaw_rates_thrust_setpoint->pitch_rate, roll_pitch_yaw_rates_thrust_setpoint->yaw_rate, roll_pitch_yaw_rates_thrust_setpoint->thrust); -} - -/** - * @brief Send a roll_pitch_yaw_rates_thrust_setpoint message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll_rate Desired roll rate in radians per second - * @param pitch_rate Desired pitch rate in radians per second - * @param yaw_rate Desired yaw rate in radians per second - * @param thrust Collective thrust, normalized to 0 .. 1 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll_rate); - _mav_put_float(buf, 8, pitch_rate); - _mav_put_float(buf, 12, yaw_rate); - _mav_put_float(buf, 16, thrust); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#endif -#else - mavlink_roll_pitch_yaw_rates_thrust_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll_rate = roll_rate; - packet.pitch_rate = pitch_rate; - packet.yaw_rate = yaw_rate; - packet.thrust = thrust; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll_rate, float pitch_rate, float yaw_rate, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll_rate); - _mav_put_float(buf, 8, pitch_rate); - _mav_put_float(buf, 12, yaw_rate); - _mav_put_float(buf, 16, thrust); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#endif -#else - mavlink_roll_pitch_yaw_rates_thrust_setpoint_t *packet = (mavlink_roll_pitch_yaw_rates_thrust_setpoint_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll_rate = roll_rate; - packet->pitch_rate = pitch_rate; - packet->yaw_rate = yaw_rate; - packet->thrust = thrust; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE ROLL_PITCH_YAW_RATES_THRUST_SETPOINT UNPACKING - - -/** - * @brief Get field time_boot_ms from roll_pitch_yaw_rates_thrust_setpoint message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll_rate from roll_pitch_yaw_rates_thrust_setpoint message - * - * @return Desired roll rate in radians per second - */ -static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_roll_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch_rate from roll_pitch_yaw_rates_thrust_setpoint message - * - * @return Desired pitch rate in radians per second - */ -static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_pitch_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw_rate from roll_pitch_yaw_rates_thrust_setpoint message - * - * @return Desired yaw rate in radians per second - */ -static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_yaw_rate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field thrust from roll_pitch_yaw_rates_thrust_setpoint message - * - * @return Collective thrust, normalized to 0 .. 1 - */ -static inline float mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a roll_pitch_yaw_rates_thrust_setpoint message into a struct - * - * @param msg The message to decode - * @param roll_pitch_yaw_rates_thrust_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_rates_thrust_setpoint_t* roll_pitch_yaw_rates_thrust_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP - roll_pitch_yaw_rates_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_time_boot_ms(msg); - roll_pitch_yaw_rates_thrust_setpoint->roll_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_roll_rate(msg); - roll_pitch_yaw_rates_thrust_setpoint->pitch_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_pitch_rate(msg); - roll_pitch_yaw_rates_thrust_setpoint->yaw_rate = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_yaw_rate(msg); - roll_pitch_yaw_rates_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_get_thrust(msg); -#else - memcpy(roll_pitch_yaw_rates_thrust_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h deleted file mode 100644 index 757e6d138..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT PACKING - -#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 59 - -typedef struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t -{ - uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot - float roll_speed; ///< Desired roll angular speed in rad/s - float pitch_speed; ///< Desired pitch angular speed in rad/s - float yaw_speed; ///< Desired yaw angular speed in rad/s - float thrust; ///< Collective thrust, normalized to 0 .. 1 -} mavlink_roll_pitch_yaw_speed_thrust_setpoint_t; - -#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20 -#define MAVLINK_MSG_ID_59_LEN 20 - -#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC 238 -#define MAVLINK_MSG_ID_59_CRC 238 - - - -#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT { \ - "ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, time_boot_ms) }, \ - { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, roll_speed) }, \ - { "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, pitch_speed) }, \ - { "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, yaw_speed) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, thrust) }, \ - } \ -} - - -/** - * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll_speed Desired roll angular speed in rad/s - * @param pitch_speed Desired pitch angular speed in rad/s - * @param yaw_speed Desired yaw angular speed in rad/s - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll_speed); - _mav_put_float(buf, 8, pitch_speed); - _mav_put_float(buf, 12, yaw_speed); - _mav_put_float(buf, 16, thrust); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#else - mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll_speed = roll_speed; - packet.pitch_speed = pitch_speed; - packet.yaw_speed = yaw_speed; - packet.thrust = thrust; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#endif -} - -/** - * @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll_speed Desired roll angular speed in rad/s - * @param pitch_speed Desired pitch angular speed in rad/s - * @param yaw_speed Desired yaw angular speed in rad/s - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float roll_speed,float pitch_speed,float yaw_speed,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll_speed); - _mav_put_float(buf, 8, pitch_speed); - _mav_put_float(buf, 12, yaw_speed); - _mav_put_float(buf, 16, thrust); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#else - mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll_speed = roll_speed; - packet.pitch_speed = pitch_speed; - packet.yaw_speed = yaw_speed; - packet.thrust = thrust; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#endif -} - -/** - * @brief Encode a roll_pitch_yaw_speed_thrust_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint) -{ - return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust); -} - -/** - * @brief Encode a roll_pitch_yaw_speed_thrust_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint) -{ - return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(system_id, component_id, chan, msg, roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust); -} - -/** - * @brief Send a roll_pitch_yaw_speed_thrust_setpoint message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll_speed Desired roll angular speed in rad/s - * @param pitch_speed Desired pitch angular speed in rad/s - * @param yaw_speed Desired yaw angular speed in rad/s - * @param thrust Collective thrust, normalized to 0 .. 1 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll_speed); - _mav_put_float(buf, 8, pitch_speed); - _mav_put_float(buf, 12, yaw_speed); - _mav_put_float(buf, 16, thrust); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#endif -#else - mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll_speed = roll_speed; - packet.pitch_speed = pitch_speed; - packet.yaw_speed = yaw_speed; - packet.thrust = thrust; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll_speed); - _mav_put_float(buf, 8, pitch_speed); - _mav_put_float(buf, 12, yaw_speed); - _mav_put_float(buf, 16, thrust); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#endif -#else - mavlink_roll_pitch_yaw_speed_thrust_setpoint_t *packet = (mavlink_roll_pitch_yaw_speed_thrust_setpoint_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll_speed = roll_speed; - packet->pitch_speed = pitch_speed; - packet->yaw_speed = yaw_speed; - packet->thrust = thrust; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING - - -/** - * @brief Get field time_boot_ms from roll_pitch_yaw_speed_thrust_setpoint message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll_speed from roll_pitch_yaw_speed_thrust_setpoint message - * - * @return Desired roll angular speed in rad/s - */ -static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch_speed from roll_pitch_yaw_speed_thrust_setpoint message - * - * @return Desired pitch angular speed in rad/s - */ -static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw_speed from roll_pitch_yaw_speed_thrust_setpoint message - * - * @return Desired yaw angular speed in rad/s - */ -static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field thrust from roll_pitch_yaw_speed_thrust_setpoint message - * - * @return Collective thrust, normalized to 0 .. 1 - */ -static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a roll_pitch_yaw_speed_thrust_setpoint message into a struct - * - * @param msg The message to decode - * @param roll_pitch_yaw_speed_thrust_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP - roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(msg); - roll_pitch_yaw_speed_thrust_setpoint->roll_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(msg); - roll_pitch_yaw_speed_thrust_setpoint->pitch_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(msg); - roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg); - roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg); -#else - memcpy(roll_pitch_yaw_speed_thrust_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h deleted file mode 100644 index f04eedcb3..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT PACKING - -#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 58 - -typedef struct __mavlink_roll_pitch_yaw_thrust_setpoint_t -{ - uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot - float roll; ///< Desired roll angle in radians - float pitch; ///< Desired pitch angle in radians - float yaw; ///< Desired yaw angle in radians - float thrust; ///< Collective thrust, normalized to 0 .. 1 -} mavlink_roll_pitch_yaw_thrust_setpoint_t; - -#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 20 -#define MAVLINK_MSG_ID_58_LEN 20 - -#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC 239 -#define MAVLINK_MSG_ID_58_CRC 239 - - - -#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT { \ - "ROLL_PITCH_YAW_THRUST_SETPOINT", \ - 5, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, time_boot_ms) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, thrust) }, \ - } \ -} - - -/** - * @brief Pack a roll_pitch_yaw_thrust_setpoint message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll angle in radians - * @param pitch Desired pitch angle in radians - * @param yaw Desired yaw angle in radians - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#else - mavlink_roll_pitch_yaw_thrust_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#endif -} - -/** - * @brief Pack a roll_pitch_yaw_thrust_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll angle in radians - * @param pitch Desired pitch angle in radians - * @param yaw Desired yaw angle in radians - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#else - mavlink_roll_pitch_yaw_thrust_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#endif -} - -/** - * @brief Encode a roll_pitch_yaw_thrust_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param roll_pitch_yaw_thrust_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint) -{ - return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_thrust_setpoint->time_boot_ms, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust); -} - -/** - * @brief Encode a roll_pitch_yaw_thrust_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param roll_pitch_yaw_thrust_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint) -{ - return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(system_id, component_id, chan, msg, roll_pitch_yaw_thrust_setpoint->time_boot_ms, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust); -} - -/** - * @brief Send a roll_pitch_yaw_thrust_setpoint message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp in milliseconds since system boot - * @param roll Desired roll angle in radians - * @param pitch Desired pitch angle in radians - * @param yaw Desired yaw angle in radians - * @param thrust Collective thrust, normalized to 0 .. 1 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#endif -#else - mavlink_roll_pitch_yaw_thrust_setpoint_t packet; - packet.time_boot_ms = time_boot_ms; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, roll); - _mav_put_float(buf, 8, pitch); - _mav_put_float(buf, 12, yaw); - _mav_put_float(buf, 16, thrust); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#endif -#else - mavlink_roll_pitch_yaw_thrust_setpoint_t *packet = (mavlink_roll_pitch_yaw_thrust_setpoint_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->thrust = thrust; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT UNPACKING - - -/** - * @brief Get field time_boot_ms from roll_pitch_yaw_thrust_setpoint message - * - * @return Timestamp in milliseconds since system boot - */ -static inline uint32_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field roll from roll_pitch_yaw_thrust_setpoint message - * - * @return Desired roll angle in radians - */ -static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field pitch from roll_pitch_yaw_thrust_setpoint message - * - * @return Desired pitch angle in radians - */ -static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from roll_pitch_yaw_thrust_setpoint message - * - * @return Desired yaw angle in radians - */ -static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field thrust from roll_pitch_yaw_thrust_setpoint message - * - * @return Collective thrust, normalized to 0 .. 1 - */ -static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a roll_pitch_yaw_thrust_setpoint message into a struct - * - * @param msg The message to decode - * @param roll_pitch_yaw_thrust_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP - roll_pitch_yaw_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(msg); - roll_pitch_yaw_thrust_setpoint->roll = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(msg); - roll_pitch_yaw_thrust_setpoint->pitch = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(msg); - roll_pitch_yaw_thrust_setpoint->yaw = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(msg); - roll_pitch_yaw_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(msg); -#else - memcpy(roll_pitch_yaw_thrust_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h deleted file mode 100644 index 0176dfcc8..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE SAFETY_ALLOWED_AREA PACKING - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55 - -typedef struct __mavlink_safety_allowed_area_t -{ - float p1x; ///< x position 1 / Latitude 1 - float p1y; ///< y position 1 / Longitude 1 - float p1z; ///< z position 1 / Altitude 1 - float p2x; ///< x position 2 / Latitude 2 - float p2y; ///< y position 2 / Longitude 2 - float p2z; ///< z position 2 / Altitude 2 - uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. -} mavlink_safety_allowed_area_t; - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25 -#define MAVLINK_MSG_ID_55_LEN 25 - -#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3 -#define MAVLINK_MSG_ID_55_CRC 3 - - - -#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \ - "SAFETY_ALLOWED_AREA", \ - 7, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \ - } \ -} - - -/** - * @brief Pack a safety_allowed_area message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif -} - -/** - * @brief Pack a safety_allowed_area message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif -} - -/** - * @brief Encode a safety_allowed_area struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param safety_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ - return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -} - -/** - * @brief Encode a safety_allowed_area struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param safety_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area) -{ - return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z); -} - -/** - * @brief Send a safety_allowed_area message - * @param chan MAVLink channel to send the message - * - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif -#else - mavlink_safety_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.frame = frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif -#else - mavlink_safety_allowed_area_t *packet = (mavlink_safety_allowed_area_t *)msgbuf; - packet->p1x = p1x; - packet->p1y = p1y; - packet->p1z = p1z; - packet->p2x = p2x; - packet->p2y = p2y; - packet->p2z = p2z; - packet->frame = frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SAFETY_ALLOWED_AREA UNPACKING - - -/** - * @brief Get field frame from safety_allowed_area message - * - * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - */ -static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field p1x from safety_allowed_area message - * - * @return x position 1 / Latitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field p1y from safety_allowed_area message - * - * @return y position 1 / Longitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field p1z from safety_allowed_area message - * - * @return z position 1 / Altitude 1 - */ -static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field p2x from safety_allowed_area message - * - * @return x position 2 / Latitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field p2y from safety_allowed_area message - * - * @return y position 2 / Longitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field p2z from safety_allowed_area message - * - * @return z position 2 / Altitude 2 - */ -static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a safety_allowed_area message into a struct - * - * @param msg The message to decode - * @param safety_allowed_area C-struct to decode the message contents into - */ -static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP - safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg); - safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg); - safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg); - safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg); - safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg); - safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg); - safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg); -#else - memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h deleted file mode 100644 index dafbc260b..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h +++ /dev/null @@ -1,401 +0,0 @@ -// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54 - -typedef struct __mavlink_safety_set_allowed_area_t -{ - float p1x; ///< x position 1 / Latitude 1 - float p1y; ///< y position 1 / Longitude 1 - float p1z; ///< z position 1 / Altitude 1 - float p2x; ///< x position 2 / Latitude 2 - float p2y; ///< y position 2 / Longitude 2 - float p2z; ///< z position 2 / Altitude 2 - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. -} mavlink_safety_set_allowed_area_t; - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27 -#define MAVLINK_MSG_ID_54_LEN 27 - -#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15 -#define MAVLINK_MSG_ID_54_CRC 15 - - - -#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \ - "SAFETY_SET_ALLOWED_AREA", \ - 9, \ - { { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \ - { "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \ - { "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \ - { "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \ - { "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \ - { "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \ - { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \ - } \ -} - - -/** - * @brief Pack a safety_set_allowed_area message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#else - mavlink_safety_set_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif -} - -/** - * @brief Pack a safety_set_allowed_area message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#else - mavlink_safety_set_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif -} - -/** - * @brief Encode a safety_set_allowed_area struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param safety_set_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ - return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -} - -/** - * @brief Encode a safety_set_allowed_area struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param safety_set_allowed_area C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_safety_set_allowed_area_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ - return mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, chan, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z); -} - -/** - * @brief Send a safety_set_allowed_area message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - * @param p1x x position 1 / Latitude 1 - * @param p1y y position 1 / Longitude 1 - * @param p1z z position 1 / Altitude 1 - * @param p2x x position 2 / Latitude 2 - * @param p2y y position 2 / Longitude 2 - * @param p2z z position 2 / Altitude 2 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN]; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif -#else - mavlink_safety_set_allowed_area_t packet; - packet.p1x = p1x; - packet.p1y = p1y; - packet.p1z = p1z; - packet.p2x = p2x; - packet.p2y = p2y; - packet.p2z = p2z; - packet.target_system = target_system; - packet.target_component = target_component; - packet.frame = frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, p1x); - _mav_put_float(buf, 4, p1y); - _mav_put_float(buf, 8, p1z); - _mav_put_float(buf, 12, p2x); - _mav_put_float(buf, 16, p2y); - _mav_put_float(buf, 20, p2z); - _mav_put_uint8_t(buf, 24, target_system); - _mav_put_uint8_t(buf, 25, target_component); - _mav_put_uint8_t(buf, 26, frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif -#else - mavlink_safety_set_allowed_area_t *packet = (mavlink_safety_set_allowed_area_t *)msgbuf; - packet->p1x = p1x; - packet->p1y = p1y; - packet->p1z = p1z; - packet->p2x = p2x; - packet->p2y = p2y; - packet->p2z = p2z; - packet->target_system = target_system; - packet->target_component = target_component; - packet->frame = frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING - - -/** - * @brief Get field target_system from safety_set_allowed_area message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field target_component from safety_set_allowed_area message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 25); -} - -/** - * @brief Get field frame from safety_set_allowed_area message - * - * @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. - */ -static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field p1x from safety_set_allowed_area message - * - * @return x position 1 / Latitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field p1y from safety_set_allowed_area message - * - * @return y position 1 / Longitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field p1z from safety_set_allowed_area message - * - * @return z position 1 / Altitude 1 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field p2x from safety_set_allowed_area message - * - * @return x position 2 / Latitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field p2y from safety_set_allowed_area message - * - * @return y position 2 / Longitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field p2z from safety_set_allowed_area message - * - * @return z position 2 / Altitude 2 - */ -static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a safety_set_allowed_area message into a struct - * - * @param msg The message to decode - * @param safety_set_allowed_area C-struct to decode the message contents into - */ -static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area) -{ -#if MAVLINK_NEED_BYTE_SWAP - safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg); - safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg); - safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg); - safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg); - safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg); - safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg); - safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg); - safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg); - safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg); -#else - memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h deleted file mode 100644 index 1648a56f8..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h +++ /dev/null @@ -1,425 +0,0 @@ -// MESSAGE SCALED_IMU PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU 26 - -typedef struct __mavlink_scaled_imu_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - int16_t xacc; ///< X acceleration (mg) - int16_t yacc; ///< Y acceleration (mg) - int16_t zacc; ///< Z acceleration (mg) - int16_t xgyro; ///< Angular speed around X axis (millirad /sec) - int16_t ygyro; ///< Angular speed around Y axis (millirad /sec) - int16_t zgyro; ///< Angular speed around Z axis (millirad /sec) - int16_t xmag; ///< X Magnetic field (milli tesla) - int16_t ymag; ///< Y Magnetic field (milli tesla) - int16_t zmag; ///< Z Magnetic field (milli tesla) -} mavlink_scaled_imu_t; - -#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22 -#define MAVLINK_MSG_ID_26_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU_CRC 170 -#define MAVLINK_MSG_ID_26_CRC 170 - - - -#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \ - "SCALED_IMU", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \ - } \ -} - - -/** - * @brief Pack a scaled_imu message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#else - mavlink_scaled_imu_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif -} - -/** - * @brief Pack a scaled_imu message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#else - mavlink_scaled_imu_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif -} - -/** - * @brief Encode a scaled_imu struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) -{ - return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); -} - -/** - * @brief Encode a scaled_imu struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu) -{ - return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag); -} - -/** - * @brief Send a scaled_imu message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif -#else - mavlink_scaled_imu_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif -#else - mavlink_scaled_imu_t *packet = (mavlink_scaled_imu_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu message - * - * @return Angular speed around X axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu message - * - * @return Angular speed around Y axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu message - * - * @return Angular speed around Z axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu message - * - * @return X Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu message - * - * @return Y Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu message - * - * @return Z Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Decode a scaled_imu message into a struct - * - * @param msg The message to decode - * @param scaled_imu C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu) -{ -#if MAVLINK_NEED_BYTE_SWAP - scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg); - scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg); - scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg); - scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg); - scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg); - scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg); - scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg); - scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg); - scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg); - scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg); -#else - memcpy(scaled_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h deleted file mode 100644 index 1dea121dd..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu2.h +++ /dev/null @@ -1,425 +0,0 @@ -// MESSAGE SCALED_IMU2 PACKING - -#define MAVLINK_MSG_ID_SCALED_IMU2 116 - -typedef struct __mavlink_scaled_imu2_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - int16_t xacc; ///< X acceleration (mg) - int16_t yacc; ///< Y acceleration (mg) - int16_t zacc; ///< Z acceleration (mg) - int16_t xgyro; ///< Angular speed around X axis (millirad /sec) - int16_t ygyro; ///< Angular speed around Y axis (millirad /sec) - int16_t zgyro; ///< Angular speed around Z axis (millirad /sec) - int16_t xmag; ///< X Magnetic field (milli tesla) - int16_t ymag; ///< Y Magnetic field (milli tesla) - int16_t zmag; ///< Z Magnetic field (milli tesla) -} mavlink_scaled_imu2_t; - -#define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22 -#define MAVLINK_MSG_ID_116_LEN 22 - -#define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76 -#define MAVLINK_MSG_ID_116_CRC 76 - - - -#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \ - "SCALED_IMU2", \ - 10, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \ - { "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \ - { "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \ - { "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \ - { "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \ - } \ -} - - -/** - * @brief Pack a scaled_imu2 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif -} - -/** - * @brief Pack a scaled_imu2 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_imu2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif -} - -/** - * @brief Encode a scaled_imu2 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_imu2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) -{ - return mavlink_msg_scaled_imu2_pack(system_id, component_id, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); -} - -/** - * @brief Encode a scaled_imu2 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_imu2 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2) -{ - return mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, chan, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag); -} - -/** - * @brief Send a scaled_imu2 message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param xacc X acceleration (mg) - * @param yacc Y acceleration (mg) - * @param zacc Z acceleration (mg) - * @param xgyro Angular speed around X axis (millirad /sec) - * @param ygyro Angular speed around Y axis (millirad /sec) - * @param zgyro Angular speed around Z axis (millirad /sec) - * @param xmag X Magnetic field (milli tesla) - * @param ymag Y Magnetic field (milli tesla) - * @param zmag Z Magnetic field (milli tesla) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_imu2_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_IMU2_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif -#else - mavlink_scaled_imu2_t packet; - packet.time_boot_ms = time_boot_ms; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.xmag = xmag; - packet.ymag = ymag; - packet.zmag = zmag; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SCALED_IMU2_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, xacc); - _mav_put_int16_t(buf, 6, yacc); - _mav_put_int16_t(buf, 8, zacc); - _mav_put_int16_t(buf, 10, xgyro); - _mav_put_int16_t(buf, 12, ygyro); - _mav_put_int16_t(buf, 14, zgyro); - _mav_put_int16_t(buf, 16, xmag); - _mav_put_int16_t(buf, 18, ymag); - _mav_put_int16_t(buf, 20, zmag); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif -#else - mavlink_scaled_imu2_t *packet = (mavlink_scaled_imu2_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->xmag = xmag; - packet->ymag = ymag; - packet->zmag = zmag; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SCALED_IMU2 UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_imu2 message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field xacc from scaled_imu2 message - * - * @return X acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field yacc from scaled_imu2 message - * - * @return Y acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field zacc from scaled_imu2 message - * - * @return Z acceleration (mg) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field xgyro from scaled_imu2 message - * - * @return Angular speed around X axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field ygyro from scaled_imu2 message - * - * @return Angular speed around Y axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field zgyro from scaled_imu2 message - * - * @return Angular speed around Z axis (millirad /sec) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field xmag from scaled_imu2 message - * - * @return X Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field ymag from scaled_imu2 message - * - * @return Y Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field zmag from scaled_imu2 message - * - * @return Z Magnetic field (milli tesla) - */ -static inline int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Decode a scaled_imu2 message into a struct - * - * @param msg The message to decode - * @param scaled_imu2 C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_imu2_decode(const mavlink_message_t* msg, mavlink_scaled_imu2_t* scaled_imu2) -{ -#if MAVLINK_NEED_BYTE_SWAP - scaled_imu2->time_boot_ms = mavlink_msg_scaled_imu2_get_time_boot_ms(msg); - scaled_imu2->xacc = mavlink_msg_scaled_imu2_get_xacc(msg); - scaled_imu2->yacc = mavlink_msg_scaled_imu2_get_yacc(msg); - scaled_imu2->zacc = mavlink_msg_scaled_imu2_get_zacc(msg); - scaled_imu2->xgyro = mavlink_msg_scaled_imu2_get_xgyro(msg); - scaled_imu2->ygyro = mavlink_msg_scaled_imu2_get_ygyro(msg); - scaled_imu2->zgyro = mavlink_msg_scaled_imu2_get_zgyro(msg); - scaled_imu2->xmag = mavlink_msg_scaled_imu2_get_xmag(msg); - scaled_imu2->ymag = mavlink_msg_scaled_imu2_get_ymag(msg); - scaled_imu2->zmag = mavlink_msg_scaled_imu2_get_zmag(msg); -#else - memcpy(scaled_imu2, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU2_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h deleted file mode 100644 index e0d6d8766..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE SCALED_PRESSURE PACKING - -#define MAVLINK_MSG_ID_SCALED_PRESSURE 29 - -typedef struct __mavlink_scaled_pressure_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - float press_abs; ///< Absolute pressure (hectopascal) - float press_diff; ///< Differential pressure 1 (hectopascal) - int16_t temperature; ///< Temperature measurement (0.01 degrees celsius) -} mavlink_scaled_pressure_t; - -#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14 -#define MAVLINK_MSG_ID_29_LEN 14 - -#define MAVLINK_MSG_ID_SCALED_PRESSURE_CRC 115 -#define MAVLINK_MSG_ID_29_CRC 115 - - - -#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \ - "SCALED_PRESSURE", \ - 4, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \ - { "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \ - { "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \ - { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \ - } \ -} - - -/** - * @brief Pack a scaled_pressure message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif -} - -/** - * @brief Pack a scaled_pressure message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif -} - -/** - * @brief Encode a scaled_pressure struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) -{ - return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); -} - -/** - * @brief Encode a scaled_pressure struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param scaled_pressure C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_scaled_pressure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure) -{ - return mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, chan, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature); -} - -/** - * @brief Send a scaled_pressure message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param press_abs Absolute pressure (hectopascal) - * @param press_diff Differential pressure 1 (hectopascal) - * @param temperature Temperature measurement (0.01 degrees celsius) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif -#else - mavlink_scaled_pressure_t packet; - packet.time_boot_ms = time_boot_ms; - packet.press_abs = press_abs; - packet.press_diff = press_diff; - packet.temperature = temperature; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_float(buf, 4, press_abs); - _mav_put_float(buf, 8, press_diff); - _mav_put_int16_t(buf, 12, temperature); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif -#else - mavlink_scaled_pressure_t *packet = (mavlink_scaled_pressure_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->press_abs = press_abs; - packet->press_diff = press_diff; - packet->temperature = temperature; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SCALED_PRESSURE UNPACKING - - -/** - * @brief Get field time_boot_ms from scaled_pressure message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field press_abs from scaled_pressure message - * - * @return Absolute pressure (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field press_diff from scaled_pressure message - * - * @return Differential pressure 1 (hectopascal) - */ -static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field temperature from scaled_pressure message - * - * @return Temperature measurement (0.01 degrees celsius) - */ -static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Decode a scaled_pressure message into a struct - * - * @param msg The message to decode - * @param scaled_pressure C-struct to decode the message contents into - */ -static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure) -{ -#if MAVLINK_NEED_BYTE_SWAP - scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg); - scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg); - scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg); - scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg); -#else - memcpy(scaled_pressure, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_PRESSURE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_serial_control.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_serial_control.h deleted file mode 100644 index cbf72bae3..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_serial_control.h +++ /dev/null @@ -1,321 +0,0 @@ -// MESSAGE SERIAL_CONTROL PACKING - -#define MAVLINK_MSG_ID_SERIAL_CONTROL 126 - -typedef struct __mavlink_serial_control_t -{ - uint32_t baudrate; ///< Baudrate of transfer. Zero means no change. - uint16_t timeout; ///< Timeout for reply data in milliseconds - uint8_t device; ///< See SERIAL_CONTROL_DEV enum - uint8_t flags; ///< See SERIAL_CONTROL_FLAG enum - uint8_t count; ///< how many bytes in this transfer - uint8_t data[70]; ///< serial data -} mavlink_serial_control_t; - -#define MAVLINK_MSG_ID_SERIAL_CONTROL_LEN 79 -#define MAVLINK_MSG_ID_126_LEN 79 - -#define MAVLINK_MSG_ID_SERIAL_CONTROL_CRC 220 -#define MAVLINK_MSG_ID_126_CRC 220 - -#define MAVLINK_MSG_SERIAL_CONTROL_FIELD_DATA_LEN 70 - -#define MAVLINK_MESSAGE_INFO_SERIAL_CONTROL { \ - "SERIAL_CONTROL", \ - 6, \ - { { "baudrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_control_t, baudrate) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_serial_control_t, timeout) }, \ - { "device", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_control_t, device) }, \ - { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_control_t, flags) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_control_t, count) }, \ - { "data", NULL, MAVLINK_TYPE_UINT8_T, 70, 9, offsetof(mavlink_serial_control_t, data) }, \ - } \ -} - - -/** - * @brief Pack a serial_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif -} - -/** - * @brief Pack a serial_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t device,uint8_t flags,uint16_t timeout,uint32_t baudrate,uint8_t count,const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif -} - -/** - * @brief Encode a serial_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) -{ - return mavlink_msg_serial_control_pack(system_id, component_id, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); -} - -/** - * @brief Encode a serial_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_control_t* serial_control) -{ - return mavlink_msg_serial_control_pack_chan(system_id, component_id, chan, msg, serial_control->device, serial_control->flags, serial_control->timeout, serial_control->baudrate, serial_control->count, serial_control->data); -} - -/** - * @brief Send a serial_control message - * @param chan MAVLink channel to send the message - * - * @param device See SERIAL_CONTROL_DEV enum - * @param flags See SERIAL_CONTROL_FLAG enum - * @param timeout Timeout for reply data in milliseconds - * @param baudrate Baudrate of transfer. Zero means no change. - * @param count how many bytes in this transfer - * @param data serial data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_control_send(mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_CONTROL_LEN]; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif -#else - mavlink_serial_control_t packet; - packet.baudrate = baudrate; - packet.timeout = timeout; - packet.device = device; - packet.flags = flags; - packet.count = count; - mav_array_memcpy(packet.data, data, sizeof(uint8_t)*70); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, uint8_t count, const uint8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, baudrate); - _mav_put_uint16_t(buf, 4, timeout); - _mav_put_uint8_t(buf, 6, device); - _mav_put_uint8_t(buf, 7, flags); - _mav_put_uint8_t(buf, 8, count); - _mav_put_uint8_t_array(buf, 9, data, 70); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, buf, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif -#else - mavlink_serial_control_t *packet = (mavlink_serial_control_t *)msgbuf; - packet->baudrate = baudrate; - packet->timeout = timeout; - packet->device = device; - packet->flags = flags; - packet->count = count; - mav_array_memcpy(packet->data, data, sizeof(uint8_t)*70); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN, MAVLINK_MSG_ID_SERIAL_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_CONTROL UNPACKING - - -/** - * @brief Get field device from serial_control message - * - * @return See SERIAL_CONTROL_DEV enum - */ -static inline uint8_t mavlink_msg_serial_control_get_device(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field flags from serial_control message - * - * @return See SERIAL_CONTROL_FLAG enum - */ -static inline uint8_t mavlink_msg_serial_control_get_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field timeout from serial_control message - * - * @return Timeout for reply data in milliseconds - */ -static inline uint16_t mavlink_msg_serial_control_get_timeout(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field baudrate from serial_control message - * - * @return Baudrate of transfer. Zero means no change. - */ -static inline uint32_t mavlink_msg_serial_control_get_baudrate(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field count from serial_control message - * - * @return how many bytes in this transfer - */ -static inline uint8_t mavlink_msg_serial_control_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field data from serial_control message - * - * @return serial data - */ -static inline uint16_t mavlink_msg_serial_control_get_data(const mavlink_message_t* msg, uint8_t *data) -{ - return _MAV_RETURN_uint8_t_array(msg, data, 70, 9); -} - -/** - * @brief Decode a serial_control message into a struct - * - * @param msg The message to decode - * @param serial_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_control_decode(const mavlink_message_t* msg, mavlink_serial_control_t* serial_control) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_control->baudrate = mavlink_msg_serial_control_get_baudrate(msg); - serial_control->timeout = mavlink_msg_serial_control_get_timeout(msg); - serial_control->device = mavlink_msg_serial_control_get_device(msg); - serial_control->flags = mavlink_msg_serial_control_get_flags(msg); - serial_control->count = mavlink_msg_serial_control_get_count(msg); - mavlink_msg_serial_control_get_data(msg, serial_control->data); -#else - memcpy(serial_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_CONTROL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h deleted file mode 100644 index e8408862f..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h +++ /dev/null @@ -1,425 +0,0 @@ -// MESSAGE SERVO_OUTPUT_RAW PACKING - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36 - -typedef struct __mavlink_servo_output_raw_t -{ - uint32_t time_usec; ///< Timestamp (microseconds since system boot) - uint16_t servo1_raw; ///< Servo output 1 value, in microseconds - uint16_t servo2_raw; ///< Servo output 2 value, in microseconds - uint16_t servo3_raw; ///< Servo output 3 value, in microseconds - uint16_t servo4_raw; ///< Servo output 4 value, in microseconds - uint16_t servo5_raw; ///< Servo output 5 value, in microseconds - uint16_t servo6_raw; ///< Servo output 6 value, in microseconds - uint16_t servo7_raw; ///< Servo output 7 value, in microseconds - uint16_t servo8_raw; ///< Servo output 8 value, in microseconds - uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. -} mavlink_servo_output_raw_t; - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21 -#define MAVLINK_MSG_ID_36_LEN 21 - -#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC 222 -#define MAVLINK_MSG_ID_36_CRC 222 - - - -#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \ - "SERVO_OUTPUT_RAW", \ - 10, \ - { { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \ - { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \ - { "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \ - { "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \ - { "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \ - { "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \ - { "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \ - { "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \ - { "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \ - { "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \ - } \ -} - - -/** - * @brief Pack a servo_output_raw message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#else - mavlink_servo_output_raw_t packet; - packet.time_usec = time_usec; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif -} - -/** - * @brief Pack a servo_output_raw message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#else - mavlink_servo_output_raw_t packet; - packet.time_usec = time_usec; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif -} - -/** - * @brief Encode a servo_output_raw struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param servo_output_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) -{ - return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); -} - -/** - * @brief Encode a servo_output_raw struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param servo_output_raw C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_servo_output_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw) -{ - return mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, chan, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw); -} - -/** - * @brief Send a servo_output_raw message - * @param chan MAVLink channel to send the message - * - * @param time_usec Timestamp (microseconds since system boot) - * @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - * @param servo1_raw Servo output 1 value, in microseconds - * @param servo2_raw Servo output 2 value, in microseconds - * @param servo3_raw Servo output 3 value, in microseconds - * @param servo4_raw Servo output 4 value, in microseconds - * @param servo5_raw Servo output 5 value, in microseconds - * @param servo6_raw Servo output 6 value, in microseconds - * @param servo7_raw Servo output 7 value, in microseconds - * @param servo8_raw Servo output 8 value, in microseconds - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN]; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif -#else - mavlink_servo_output_raw_t packet; - packet.time_usec = time_usec; - packet.servo1_raw = servo1_raw; - packet.servo2_raw = servo2_raw; - packet.servo3_raw = servo3_raw; - packet.servo4_raw = servo4_raw; - packet.servo5_raw = servo5_raw; - packet.servo6_raw = servo6_raw; - packet.servo7_raw = servo7_raw; - packet.servo8_raw = servo8_raw; - packet.port = port; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_servo_output_raw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_usec); - _mav_put_uint16_t(buf, 4, servo1_raw); - _mav_put_uint16_t(buf, 6, servo2_raw); - _mav_put_uint16_t(buf, 8, servo3_raw); - _mav_put_uint16_t(buf, 10, servo4_raw); - _mav_put_uint16_t(buf, 12, servo5_raw); - _mav_put_uint16_t(buf, 14, servo6_raw); - _mav_put_uint16_t(buf, 16, servo7_raw); - _mav_put_uint16_t(buf, 18, servo8_raw); - _mav_put_uint8_t(buf, 20, port); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif -#else - mavlink_servo_output_raw_t *packet = (mavlink_servo_output_raw_t *)msgbuf; - packet->time_usec = time_usec; - packet->servo1_raw = servo1_raw; - packet->servo2_raw = servo2_raw; - packet->servo3_raw = servo3_raw; - packet->servo4_raw = servo4_raw; - packet->servo5_raw = servo5_raw; - packet->servo6_raw = servo6_raw; - packet->servo7_raw = servo7_raw; - packet->servo8_raw = servo8_raw; - packet->port = port; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)packet, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERVO_OUTPUT_RAW UNPACKING - - -/** - * @brief Get field time_usec from servo_output_raw message - * - * @return Timestamp (microseconds since system boot) - */ -static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field port from servo_output_raw message - * - * @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. - */ -static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field servo1_raw from servo_output_raw message - * - * @return Servo output 1 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field servo2_raw from servo_output_raw message - * - * @return Servo output 2 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field servo3_raw from servo_output_raw message - * - * @return Servo output 3 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field servo4_raw from servo_output_raw message - * - * @return Servo output 4 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field servo5_raw from servo_output_raw message - * - * @return Servo output 5 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field servo6_raw from servo_output_raw message - * - * @return Servo output 6 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field servo7_raw from servo_output_raw message - * - * @return Servo output 7 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field servo8_raw from servo_output_raw message - * - * @return Servo output 8 value, in microseconds - */ -static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Decode a servo_output_raw message into a struct - * - * @param msg The message to decode - * @param servo_output_raw C-struct to decode the message contents into - */ -static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw) -{ -#if MAVLINK_NEED_BYTE_SWAP - servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg); - servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg); - servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg); - servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg); - servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg); - servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg); - servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg); - servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg); - servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg); - servo_output_raw->port = mavlink_msg_servo_output_raw_get_port(msg); -#else - memcpy(servo_output_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h deleted file mode 100644 index 94a7b432b..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT PACKING - -#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT 53 - -typedef struct __mavlink_set_global_position_setpoint_int_t -{ - int32_t latitude; ///< Latitude (WGS84), in degrees * 1E7 - int32_t longitude; ///< Longitude (WGS84), in degrees * 1E7 - int32_t altitude; ///< Altitude (WGS84), in meters * 1000 (positive for up) - int16_t yaw; ///< Desired yaw angle in degrees * 100 - uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT -} mavlink_set_global_position_setpoint_int_t; - -#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN 15 -#define MAVLINK_MSG_ID_53_LEN 15 - -#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC 33 -#define MAVLINK_MSG_ID_53_CRC 33 - - - -#define MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT { \ - "SET_GLOBAL_POSITION_SETPOINT_INT", \ - 5, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_global_position_setpoint_int_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_global_position_setpoint_int_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_global_position_setpoint_int_t, altitude) }, \ - { "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_set_global_position_setpoint_int_t, yaw) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_set_global_position_setpoint_int_t, coordinate_frame) }, \ - } \ -} - - -/** - * @brief Pack a set_global_position_setpoint_int message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @param yaw Desired yaw angle in degrees * 100 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_int16_t(buf, 12, yaw); - _mav_put_uint8_t(buf, 14, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#else - mavlink_set_global_position_setpoint_int_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.yaw = yaw; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -} - -/** - * @brief Pack a set_global_position_setpoint_int message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @param yaw Desired yaw angle in degrees * 100 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_int16_t(buf, 12, yaw); - _mav_put_uint8_t(buf, 14, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#else - mavlink_set_global_position_setpoint_int_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.yaw = yaw; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -} - -/** - * @brief Encode a set_global_position_setpoint_int struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_global_position_setpoint_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int) -{ - return mavlink_msg_set_global_position_setpoint_int_pack(system_id, component_id, msg, set_global_position_setpoint_int->coordinate_frame, set_global_position_setpoint_int->latitude, set_global_position_setpoint_int->longitude, set_global_position_setpoint_int->altitude, set_global_position_setpoint_int->yaw); -} - -/** - * @brief Encode a set_global_position_setpoint_int struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_global_position_setpoint_int C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int) -{ - return mavlink_msg_set_global_position_setpoint_int_pack_chan(system_id, component_id, chan, msg, set_global_position_setpoint_int->coordinate_frame, set_global_position_setpoint_int->latitude, set_global_position_setpoint_int->longitude, set_global_position_setpoint_int->altitude, set_global_position_setpoint_int->yaw); -} - -/** - * @brief Send a set_global_position_setpoint_int message - * @param chan MAVLink channel to send the message - * - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84), in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @param yaw Desired yaw angle in degrees * 100 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_int16_t(buf, 12, yaw); - _mav_put_uint8_t(buf, 14, coordinate_frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -#else - mavlink_set_global_position_setpoint_int_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.yaw = yaw; - packet.coordinate_frame = coordinate_frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_global_position_setpoint_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_int16_t(buf, 12, yaw); - _mav_put_uint8_t(buf, 14, coordinate_frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -#else - mavlink_set_global_position_setpoint_int_t *packet = (mavlink_set_global_position_setpoint_int_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->yaw = yaw; - packet->coordinate_frame = coordinate_frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)packet, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT UNPACKING - - -/** - * @brief Get field coordinate_frame from set_global_position_setpoint_int message - * - * @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT - */ -static inline uint8_t mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Get field latitude from set_global_position_setpoint_int message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from set_global_position_setpoint_int message - * - * @return Longitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from set_global_position_setpoint_int message - * - * @return Altitude (WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field yaw from set_global_position_setpoint_int message - * - * @return Desired yaw angle in degrees * 100 - */ -static inline int16_t mavlink_msg_set_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Decode a set_global_position_setpoint_int message into a struct - * - * @param msg The message to decode - * @param set_global_position_setpoint_int C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_global_position_setpoint_int_decode(const mavlink_message_t* msg, mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_global_position_setpoint_int->latitude = mavlink_msg_set_global_position_setpoint_int_get_latitude(msg); - set_global_position_setpoint_int->longitude = mavlink_msg_set_global_position_setpoint_int_get_longitude(msg); - set_global_position_setpoint_int->altitude = mavlink_msg_set_global_position_setpoint_int_get_altitude(msg); - set_global_position_setpoint_int->yaw = mavlink_msg_set_global_position_setpoint_int_get_yaw(msg); - set_global_position_setpoint_int->coordinate_frame = mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(msg); -#else - memcpy(set_global_position_setpoint_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h deleted file mode 100644 index 1c018cbee..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48 - -typedef struct __mavlink_set_gps_global_origin_t -{ - int32_t latitude; ///< Latitude (WGS84), in degrees * 1E7 - int32_t longitude; ///< Longitude (WGS84, in degrees * 1E7 - int32_t altitude; ///< Altitude (WGS84), in meters * 1000 (positive for up) - uint8_t target_system; ///< System ID -} mavlink_set_gps_global_origin_t; - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13 -#define MAVLINK_MSG_ID_48_LEN 13 - -#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC 41 -#define MAVLINK_MSG_ID_48_CRC 41 - - - -#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \ - "SET_GPS_GLOBAL_ORIGIN", \ - 4, \ - { { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \ - { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \ - { "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \ - } \ -} - - -/** - * @brief Pack a set_gps_global_origin message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint8_t(buf, 12, target_system); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif -} - -/** - * @brief Pack a set_gps_global_origin message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint8_t(buf, 12, target_system); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif -} - -/** - * @brief Encode a set_gps_global_origin struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ - return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); -} - -/** - * @brief Encode a set_gps_global_origin struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_gps_global_origin C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_gps_global_origin_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ - return mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, chan, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude); -} - -/** - * @brief Send a set_gps_global_origin message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param latitude Latitude (WGS84), in degrees * 1E7 - * @param longitude Longitude (WGS84, in degrees * 1E7 - * @param altitude Altitude (WGS84), in meters * 1000 (positive for up) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN]; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint8_t(buf, 12, target_system); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif -#else - mavlink_set_gps_global_origin_t packet; - packet.latitude = latitude; - packet.longitude = longitude; - packet.altitude = altitude; - packet.target_system = target_system; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, latitude); - _mav_put_int32_t(buf, 4, longitude); - _mav_put_int32_t(buf, 8, altitude); - _mav_put_uint8_t(buf, 12, target_system); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif -#else - mavlink_set_gps_global_origin_t *packet = (mavlink_set_gps_global_origin_t *)msgbuf; - packet->latitude = latitude; - packet->longitude = longitude; - packet->altitude = altitude; - packet->target_system = target_system; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING - - -/** - * @brief Get field target_system from set_gps_global_origin message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field latitude from set_gps_global_origin message - * - * @return Latitude (WGS84), in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field longitude from set_gps_global_origin message - * - * @return Longitude (WGS84, in degrees * 1E7 - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field altitude from set_gps_global_origin message - * - * @return Altitude (WGS84), in meters * 1000 (positive for up) - */ -static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Decode a set_gps_global_origin message into a struct - * - * @param msg The message to decode - * @param set_gps_global_origin C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_set_gps_global_origin_t* set_gps_global_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_gps_global_origin->latitude = mavlink_msg_set_gps_global_origin_get_latitude(msg); - set_gps_global_origin->longitude = mavlink_msg_set_gps_global_origin_get_longitude(msg); - set_gps_global_origin->altitude = mavlink_msg_set_gps_global_origin_get_altitude(msg); - set_gps_global_origin->target_system = mavlink_msg_set_gps_global_origin_get_target_system(msg); -#else - memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h deleted file mode 100644 index 04dbe6e9a..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE SET_LOCAL_POSITION_SETPOINT PACKING - -#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT 50 - -typedef struct __mavlink_set_local_position_setpoint_t -{ - float x; ///< x position - float y; ///< y position - float z; ///< z position - float yaw; ///< Desired yaw angle - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU -} mavlink_set_local_position_setpoint_t; - -#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN 19 -#define MAVLINK_MSG_ID_50_LEN 19 - -#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC 214 -#define MAVLINK_MSG_ID_50_CRC 214 - - - -#define MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT { \ - "SET_LOCAL_POSITION_SETPOINT", \ - 7, \ - { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_local_position_setpoint_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_local_position_setpoint_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_local_position_setpoint_t, z) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_local_position_setpoint_t, yaw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_local_position_setpoint_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_local_position_setpoint_t, target_component) }, \ - { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_set_local_position_setpoint_t, coordinate_frame) }, \ - } \ -} - - -/** - * @brief Pack a set_local_position_setpoint message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - * @param x x position - * @param y y position - * @param z z position - * @param yaw Desired yaw angle - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - _mav_put_uint8_t(buf, 18, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#else - mavlink_set_local_position_setpoint_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#endif -} - -/** - * @brief Pack a set_local_position_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - * @param x x position - * @param y y position - * @param z z position - * @param yaw Desired yaw angle - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,float x,float y,float z,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - _mav_put_uint8_t(buf, 18, coordinate_frame); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#else - mavlink_set_local_position_setpoint_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#endif -} - -/** - * @brief Encode a set_local_position_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_local_position_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_local_position_setpoint_t* set_local_position_setpoint) -{ - return mavlink_msg_set_local_position_setpoint_pack(system_id, component_id, msg, set_local_position_setpoint->target_system, set_local_position_setpoint->target_component, set_local_position_setpoint->coordinate_frame, set_local_position_setpoint->x, set_local_position_setpoint->y, set_local_position_setpoint->z, set_local_position_setpoint->yaw); -} - -/** - * @brief Encode a set_local_position_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_local_position_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_local_position_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_local_position_setpoint_t* set_local_position_setpoint) -{ - return mavlink_msg_set_local_position_setpoint_pack_chan(system_id, component_id, chan, msg, set_local_position_setpoint->target_system, set_local_position_setpoint->target_component, set_local_position_setpoint->coordinate_frame, set_local_position_setpoint->x, set_local_position_setpoint->y, set_local_position_setpoint->z, set_local_position_setpoint->yaw); -} - -/** - * @brief Send a set_local_position_setpoint message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - * @param x x position - * @param y y position - * @param z z position - * @param yaw Desired yaw angle - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_local_position_setpoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - _mav_put_uint8_t(buf, 18, coordinate_frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#endif -#else - mavlink_set_local_position_setpoint_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.target_system = target_system; - packet.target_component = target_component; - packet.coordinate_frame = coordinate_frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_local_position_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - _mav_put_uint8_t(buf, 18, coordinate_frame); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#endif -#else - mavlink_set_local_position_setpoint_t *packet = (mavlink_set_local_position_setpoint_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->yaw = yaw; - packet->target_system = target_system; - packet->target_component = target_component; - packet->coordinate_frame = coordinate_frame; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_LOCAL_POSITION_SETPOINT UNPACKING - - -/** - * @brief Get field target_system from set_local_position_setpoint message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_local_position_setpoint_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from set_local_position_setpoint message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_local_position_setpoint_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field coordinate_frame from set_local_position_setpoint message - * - * @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU - */ -static inline uint8_t mavlink_msg_set_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field x from set_local_position_setpoint message - * - * @return x position - */ -static inline float mavlink_msg_set_local_position_setpoint_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field y from set_local_position_setpoint message - * - * @return y position - */ -static inline float mavlink_msg_set_local_position_setpoint_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field z from set_local_position_setpoint message - * - * @return z position - */ -static inline float mavlink_msg_set_local_position_setpoint_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from set_local_position_setpoint message - * - * @return Desired yaw angle - */ -static inline float mavlink_msg_set_local_position_setpoint_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a set_local_position_setpoint message into a struct - * - * @param msg The message to decode - * @param set_local_position_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_set_local_position_setpoint_t* set_local_position_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_local_position_setpoint->x = mavlink_msg_set_local_position_setpoint_get_x(msg); - set_local_position_setpoint->y = mavlink_msg_set_local_position_setpoint_get_y(msg); - set_local_position_setpoint->z = mavlink_msg_set_local_position_setpoint_get_z(msg); - set_local_position_setpoint->yaw = mavlink_msg_set_local_position_setpoint_get_yaw(msg); - set_local_position_setpoint->target_system = mavlink_msg_set_local_position_setpoint_get_target_system(msg); - set_local_position_setpoint->target_component = mavlink_msg_set_local_position_setpoint_get_target_component(msg); - set_local_position_setpoint->coordinate_frame = mavlink_msg_set_local_position_setpoint_get_coordinate_frame(msg); -#else - memcpy(set_local_position_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h deleted file mode 100644 index 4b60a4120..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE SET_MODE PACKING - -#define MAVLINK_MSG_ID_SET_MODE 11 - -typedef struct __mavlink_set_mode_t -{ - uint32_t custom_mode; ///< The new autopilot-specific mode. This field can be ignored by an autopilot. - uint8_t target_system; ///< The system setting the mode - uint8_t base_mode; ///< The new base mode -} mavlink_set_mode_t; - -#define MAVLINK_MSG_ID_SET_MODE_LEN 6 -#define MAVLINK_MSG_ID_11_LEN 6 - -#define MAVLINK_MSG_ID_SET_MODE_CRC 89 -#define MAVLINK_MSG_ID_11_CRC 89 - - - -#define MAVLINK_MESSAGE_INFO_SET_MODE { \ - "SET_MODE", \ - 3, \ - { { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \ - { "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \ - } \ -} - - -/** - * @brief Pack a set_mode message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, base_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); -#else - mavlink_set_mode_t packet; - packet.custom_mode = custom_mode; - packet.target_system = target_system; - packet.base_mode = base_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_MODE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif -} - -/** - * @brief Pack a set_mode message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t base_mode,uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, base_mode); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MODE_LEN); -#else - mavlink_set_mode_t packet; - packet.custom_mode = custom_mode; - packet.target_system = target_system; - packet.base_mode = base_mode; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_MODE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif -} - -/** - * @brief Encode a set_mode struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_mode C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) -{ - return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -} - -/** - * @brief Encode a set_mode struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_mode C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_mode_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode) -{ - return mavlink_msg_set_mode_pack_chan(system_id, component_id, chan, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode); -} - -/** - * @brief Send a set_mode message - * @param chan MAVLink channel to send the message - * - * @param target_system The system setting the mode - * @param base_mode The new base mode - * @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_MODE_LEN]; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, base_mode); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif -#else - mavlink_set_mode_t packet; - packet.custom_mode = custom_mode; - packet.target_system = target_system; - packet.base_mode = base_mode; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_MODE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_mode_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, custom_mode); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, base_mode); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif -#else - mavlink_set_mode_t *packet = (mavlink_set_mode_t *)msgbuf; - packet->custom_mode = custom_mode; - packet->target_system = target_system; - packet->base_mode = base_mode; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN, MAVLINK_MSG_ID_SET_MODE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)packet, MAVLINK_MSG_ID_SET_MODE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_MODE UNPACKING - - -/** - * @brief Get field target_system from set_mode message - * - * @return The system setting the mode - */ -static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field base_mode from set_mode message - * - * @return The new base mode - */ -static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field custom_mode from set_mode message - * - * @return The new autopilot-specific mode. This field can be ignored by an autopilot. - */ -static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Decode a set_mode message into a struct - * - * @param msg The message to decode - * @param set_mode C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg); - set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg); - set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg); -#else - memcpy(set_mode, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_MODE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h deleted file mode 100644 index 8c0e2a014..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE SET_QUAD_MOTORS_SETPOINT PACKING - -#define MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT 60 - -typedef struct __mavlink_set_quad_motors_setpoint_t -{ - uint16_t motor_front_nw; ///< Front motor in + configuration, front left motor in x configuration - uint16_t motor_right_ne; ///< Right motor in + configuration, front right motor in x configuration - uint16_t motor_back_se; ///< Back motor in + configuration, back right motor in x configuration - uint16_t motor_left_sw; ///< Left motor in + configuration, back left motor in x configuration - uint8_t target_system; ///< System ID of the system that should set these motor commands -} mavlink_set_quad_motors_setpoint_t; - -#define MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN 9 -#define MAVLINK_MSG_ID_60_LEN 9 - -#define MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC 30 -#define MAVLINK_MSG_ID_60_CRC 30 - - - -#define MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT { \ - "SET_QUAD_MOTORS_SETPOINT", \ - 5, \ - { { "motor_front_nw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_set_quad_motors_setpoint_t, motor_front_nw) }, \ - { "motor_right_ne", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_set_quad_motors_setpoint_t, motor_right_ne) }, \ - { "motor_back_se", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_set_quad_motors_setpoint_t, motor_back_se) }, \ - { "motor_left_sw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_set_quad_motors_setpoint_t, motor_left_sw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_set_quad_motors_setpoint_t, target_system) }, \ - } \ -} - - -/** - * @brief Pack a set_quad_motors_setpoint message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID of the system that should set these motor commands - * @param motor_front_nw Front motor in + configuration, front left motor in x configuration - * @param motor_right_ne Right motor in + configuration, front right motor in x configuration - * @param motor_back_se Back motor in + configuration, back right motor in x configuration - * @param motor_left_sw Left motor in + configuration, back left motor in x configuration - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN]; - _mav_put_uint16_t(buf, 0, motor_front_nw); - _mav_put_uint16_t(buf, 2, motor_right_ne); - _mav_put_uint16_t(buf, 4, motor_back_se); - _mav_put_uint16_t(buf, 6, motor_left_sw); - _mav_put_uint8_t(buf, 8, target_system); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#else - mavlink_set_quad_motors_setpoint_t packet; - packet.motor_front_nw = motor_front_nw; - packet.motor_right_ne = motor_right_ne; - packet.motor_back_se = motor_back_se; - packet.motor_left_sw = motor_left_sw; - packet.target_system = target_system; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#endif -} - -/** - * @brief Pack a set_quad_motors_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID of the system that should set these motor commands - * @param motor_front_nw Front motor in + configuration, front left motor in x configuration - * @param motor_right_ne Right motor in + configuration, front right motor in x configuration - * @param motor_back_se Back motor in + configuration, back right motor in x configuration - * @param motor_left_sw Left motor in + configuration, back left motor in x configuration - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint16_t motor_front_nw,uint16_t motor_right_ne,uint16_t motor_back_se,uint16_t motor_left_sw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN]; - _mav_put_uint16_t(buf, 0, motor_front_nw); - _mav_put_uint16_t(buf, 2, motor_right_ne); - _mav_put_uint16_t(buf, 4, motor_back_se); - _mav_put_uint16_t(buf, 6, motor_left_sw); - _mav_put_uint8_t(buf, 8, target_system); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#else - mavlink_set_quad_motors_setpoint_t packet; - packet.motor_front_nw = motor_front_nw; - packet.motor_right_ne = motor_right_ne; - packet.motor_back_se = motor_back_se; - packet.motor_left_sw = motor_left_sw; - packet.target_system = target_system; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#endif -} - -/** - * @brief Encode a set_quad_motors_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_quad_motors_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_quad_motors_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_quad_motors_setpoint_t* set_quad_motors_setpoint) -{ - return mavlink_msg_set_quad_motors_setpoint_pack(system_id, component_id, msg, set_quad_motors_setpoint->target_system, set_quad_motors_setpoint->motor_front_nw, set_quad_motors_setpoint->motor_right_ne, set_quad_motors_setpoint->motor_back_se, set_quad_motors_setpoint->motor_left_sw); -} - -/** - * @brief Encode a set_quad_motors_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_quad_motors_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_quad_motors_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_quad_motors_setpoint_t* set_quad_motors_setpoint) -{ - return mavlink_msg_set_quad_motors_setpoint_pack_chan(system_id, component_id, chan, msg, set_quad_motors_setpoint->target_system, set_quad_motors_setpoint->motor_front_nw, set_quad_motors_setpoint->motor_right_ne, set_quad_motors_setpoint->motor_back_se, set_quad_motors_setpoint->motor_left_sw); -} - -/** - * @brief Send a set_quad_motors_setpoint message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID of the system that should set these motor commands - * @param motor_front_nw Front motor in + configuration, front left motor in x configuration - * @param motor_right_ne Right motor in + configuration, front right motor in x configuration - * @param motor_back_se Back motor in + configuration, back right motor in x configuration - * @param motor_left_sw Left motor in + configuration, back left motor in x configuration - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_quad_motors_setpoint_send(mavlink_channel_t chan, uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN]; - _mav_put_uint16_t(buf, 0, motor_front_nw); - _mav_put_uint16_t(buf, 2, motor_right_ne); - _mav_put_uint16_t(buf, 4, motor_back_se); - _mav_put_uint16_t(buf, 6, motor_left_sw); - _mav_put_uint8_t(buf, 8, target_system); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#endif -#else - mavlink_set_quad_motors_setpoint_t packet; - packet.motor_front_nw = motor_front_nw; - packet.motor_right_ne = motor_right_ne; - packet.motor_back_se = motor_back_se; - packet.motor_left_sw = motor_left_sw; - packet.target_system = target_system; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_quad_motors_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, motor_front_nw); - _mav_put_uint16_t(buf, 2, motor_right_ne); - _mav_put_uint16_t(buf, 4, motor_back_se); - _mav_put_uint16_t(buf, 6, motor_left_sw); - _mav_put_uint8_t(buf, 8, target_system); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#endif -#else - mavlink_set_quad_motors_setpoint_t *packet = (mavlink_set_quad_motors_setpoint_t *)msgbuf; - packet->motor_front_nw = motor_front_nw; - packet->motor_right_ne = motor_right_ne; - packet->motor_back_se = motor_back_se; - packet->motor_left_sw = motor_left_sw; - packet->target_system = target_system; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_QUAD_MOTORS_SETPOINT UNPACKING - - -/** - * @brief Get field target_system from set_quad_motors_setpoint message - * - * @return System ID of the system that should set these motor commands - */ -static inline uint8_t mavlink_msg_set_quad_motors_setpoint_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field motor_front_nw from set_quad_motors_setpoint message - * - * @return Front motor in + configuration, front left motor in x configuration - */ -static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_front_nw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field motor_right_ne from set_quad_motors_setpoint message - * - * @return Right motor in + configuration, front right motor in x configuration - */ -static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_right_ne(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field motor_back_se from set_quad_motors_setpoint message - * - * @return Back motor in + configuration, back right motor in x configuration - */ -static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_back_se(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field motor_left_sw from set_quad_motors_setpoint message - * - * @return Left motor in + configuration, back left motor in x configuration - */ -static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_left_sw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Decode a set_quad_motors_setpoint message into a struct - * - * @param msg The message to decode - * @param set_quad_motors_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_quad_motors_setpoint_decode(const mavlink_message_t* msg, mavlink_set_quad_motors_setpoint_t* set_quad_motors_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_quad_motors_setpoint->motor_front_nw = mavlink_msg_set_quad_motors_setpoint_get_motor_front_nw(msg); - set_quad_motors_setpoint->motor_right_ne = mavlink_msg_set_quad_motors_setpoint_get_motor_right_ne(msg); - set_quad_motors_setpoint->motor_back_se = mavlink_msg_set_quad_motors_setpoint_get_motor_back_se(msg); - set_quad_motors_setpoint->motor_left_sw = mavlink_msg_set_quad_motors_setpoint_get_motor_left_sw(msg); - set_quad_motors_setpoint->target_system = mavlink_msg_set_quad_motors_setpoint_get_target_system(msg); -#else - memcpy(set_quad_motors_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h deleted file mode 100644 index c9a084773..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust.h +++ /dev/null @@ -1,399 +0,0 @@ -// MESSAGE SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST PACKING - -#define MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST 63 - -typedef struct __mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t -{ - int16_t roll[4]; ///< Desired roll angle in radians +-PI (+-INT16_MAX) - int16_t pitch[4]; ///< Desired pitch angle in radians +-PI (+-INT16_MAX) - int16_t yaw[4]; ///< Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - uint16_t thrust[4]; ///< Collective thrust, scaled to uint16 (0..UINT16_MAX) - uint8_t group; ///< ID of the quadrotor group (0 - 255, up to 256 groups supported) - uint8_t mode; ///< ID of the flight mode (0 - 255, up to 256 modes supported) - uint8_t led_red[4]; ///< RGB red channel (0-255) - uint8_t led_blue[4]; ///< RGB green channel (0-255) - uint8_t led_green[4]; ///< RGB blue channel (0-255) -} mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t; - -#define MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN 46 -#define MAVLINK_MSG_ID_63_LEN 46 - -#define MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC 130 -#define MAVLINK_MSG_ID_63_CRC 130 - -#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_ROLL_LEN 4 -#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_PITCH_LEN 4 -#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_YAW_LEN 4 -#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_THRUST_LEN 4 -#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_LED_RED_LEN 4 -#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_LED_BLUE_LEN 4 -#define MAVLINK_MSG_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_FIELD_LED_GREEN_LEN 4 - -#define MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST { \ - "SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST", \ - 9, \ - { { "roll", NULL, MAVLINK_TYPE_INT16_T, 4, 0, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_INT16_T, 4, 8, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_INT16_T, 4, 16, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, thrust) }, \ - { "group", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, group) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, mode) }, \ - { "led_red", NULL, MAVLINK_TYPE_UINT8_T, 4, 34, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, led_red) }, \ - { "led_blue", NULL, MAVLINK_TYPE_UINT8_T, 4, 38, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, led_blue) }, \ - { "led_green", NULL, MAVLINK_TYPE_UINT8_T, 4, 42, offsetof(mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t, led_green) }, \ - } \ -} - - -/** - * @brief Pack a set_quad_swarm_led_roll_pitch_yaw_thrust message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param group ID of the quadrotor group (0 - 255, up to 256 groups supported) - * @param mode ID of the flight mode (0 - 255, up to 256 modes supported) - * @param led_red RGB red channel (0-255) - * @param led_blue RGB green channel (0-255) - * @param led_green RGB blue channel (0-255) - * @param roll Desired roll angle in radians +-PI (+-INT16_MAX) - * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX) - * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t group, uint8_t mode, const uint8_t *led_red, const uint8_t *led_blue, const uint8_t *led_green, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN]; - _mav_put_uint8_t(buf, 32, group); - _mav_put_uint8_t(buf, 33, mode); - _mav_put_int16_t_array(buf, 0, roll, 4); - _mav_put_int16_t_array(buf, 8, pitch, 4); - _mav_put_int16_t_array(buf, 16, yaw, 4); - _mav_put_uint16_t_array(buf, 24, thrust, 4); - _mav_put_uint8_t_array(buf, 34, led_red, 4); - _mav_put_uint8_t_array(buf, 38, led_blue, 4); - _mav_put_uint8_t_array(buf, 42, led_green, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#else - mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet; - packet.group = group; - packet.mode = mode; - mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4); - mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4); - mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4); - mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4); - mav_array_memcpy(packet.led_red, led_red, sizeof(uint8_t)*4); - mav_array_memcpy(packet.led_blue, led_blue, sizeof(uint8_t)*4); - mav_array_memcpy(packet.led_green, led_green, sizeof(uint8_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#endif -} - -/** - * @brief Pack a set_quad_swarm_led_roll_pitch_yaw_thrust message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param group ID of the quadrotor group (0 - 255, up to 256 groups supported) - * @param mode ID of the flight mode (0 - 255, up to 256 modes supported) - * @param led_red RGB red channel (0-255) - * @param led_blue RGB green channel (0-255) - * @param led_green RGB blue channel (0-255) - * @param roll Desired roll angle in radians +-PI (+-INT16_MAX) - * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX) - * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t group,uint8_t mode,const uint8_t *led_red,const uint8_t *led_blue,const uint8_t *led_green,const int16_t *roll,const int16_t *pitch,const int16_t *yaw,const uint16_t *thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN]; - _mav_put_uint8_t(buf, 32, group); - _mav_put_uint8_t(buf, 33, mode); - _mav_put_int16_t_array(buf, 0, roll, 4); - _mav_put_int16_t_array(buf, 8, pitch, 4); - _mav_put_int16_t_array(buf, 16, yaw, 4); - _mav_put_uint16_t_array(buf, 24, thrust, 4); - _mav_put_uint8_t_array(buf, 34, led_red, 4); - _mav_put_uint8_t_array(buf, 38, led_blue, 4); - _mav_put_uint8_t_array(buf, 42, led_green, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#else - mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet; - packet.group = group; - packet.mode = mode; - mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4); - mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4); - mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4); - mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4); - mav_array_memcpy(packet.led_red, led_red, sizeof(uint8_t)*4); - mav_array_memcpy(packet.led_blue, led_blue, sizeof(uint8_t)*4); - mav_array_memcpy(packet.led_green, led_green, sizeof(uint8_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#endif -} - -/** - * @brief Encode a set_quad_swarm_led_roll_pitch_yaw_thrust struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_quad_swarm_led_roll_pitch_yaw_thrust C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t* set_quad_swarm_led_roll_pitch_yaw_thrust) -{ - return mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_quad_swarm_led_roll_pitch_yaw_thrust->group, set_quad_swarm_led_roll_pitch_yaw_thrust->mode, set_quad_swarm_led_roll_pitch_yaw_thrust->led_red, set_quad_swarm_led_roll_pitch_yaw_thrust->led_blue, set_quad_swarm_led_roll_pitch_yaw_thrust->led_green, set_quad_swarm_led_roll_pitch_yaw_thrust->roll, set_quad_swarm_led_roll_pitch_yaw_thrust->pitch, set_quad_swarm_led_roll_pitch_yaw_thrust->yaw, set_quad_swarm_led_roll_pitch_yaw_thrust->thrust); -} - -/** - * @brief Encode a set_quad_swarm_led_roll_pitch_yaw_thrust struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_quad_swarm_led_roll_pitch_yaw_thrust C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t* set_quad_swarm_led_roll_pitch_yaw_thrust) -{ - return mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, chan, msg, set_quad_swarm_led_roll_pitch_yaw_thrust->group, set_quad_swarm_led_roll_pitch_yaw_thrust->mode, set_quad_swarm_led_roll_pitch_yaw_thrust->led_red, set_quad_swarm_led_roll_pitch_yaw_thrust->led_blue, set_quad_swarm_led_roll_pitch_yaw_thrust->led_green, set_quad_swarm_led_roll_pitch_yaw_thrust->roll, set_quad_swarm_led_roll_pitch_yaw_thrust->pitch, set_quad_swarm_led_roll_pitch_yaw_thrust->yaw, set_quad_swarm_led_roll_pitch_yaw_thrust->thrust); -} - -/** - * @brief Send a set_quad_swarm_led_roll_pitch_yaw_thrust message - * @param chan MAVLink channel to send the message - * - * @param group ID of the quadrotor group (0 - 255, up to 256 groups supported) - * @param mode ID of the flight mode (0 - 255, up to 256 modes supported) - * @param led_red RGB red channel (0-255) - * @param led_blue RGB green channel (0-255) - * @param led_green RGB blue channel (0-255) - * @param roll Desired roll angle in radians +-PI (+-INT16_MAX) - * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX) - * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t group, uint8_t mode, const uint8_t *led_red, const uint8_t *led_blue, const uint8_t *led_green, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN]; - _mav_put_uint8_t(buf, 32, group); - _mav_put_uint8_t(buf, 33, mode); - _mav_put_int16_t_array(buf, 0, roll, 4); - _mav_put_int16_t_array(buf, 8, pitch, 4); - _mav_put_int16_t_array(buf, 16, yaw, 4); - _mav_put_uint16_t_array(buf, 24, thrust, 4); - _mav_put_uint8_t_array(buf, 34, led_red, 4); - _mav_put_uint8_t_array(buf, 38, led_blue, 4); - _mav_put_uint8_t_array(buf, 42, led_green, 4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#else - mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t packet; - packet.group = group; - packet.mode = mode; - mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4); - mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4); - mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4); - mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4); - mav_array_memcpy(packet.led_red, led_red, sizeof(uint8_t)*4); - mav_array_memcpy(packet.led_blue, led_blue, sizeof(uint8_t)*4); - mav_array_memcpy(packet.led_green, led_green, sizeof(uint8_t)*4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t group, uint8_t mode, const uint8_t *led_red, const uint8_t *led_blue, const uint8_t *led_green, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 32, group); - _mav_put_uint8_t(buf, 33, mode); - _mav_put_int16_t_array(buf, 0, roll, 4); - _mav_put_int16_t_array(buf, 8, pitch, 4); - _mav_put_int16_t_array(buf, 16, yaw, 4); - _mav_put_uint16_t_array(buf, 24, thrust, 4); - _mav_put_uint8_t_array(buf, 34, led_red, 4); - _mav_put_uint8_t_array(buf, 38, led_blue, 4); - _mav_put_uint8_t_array(buf, 42, led_green, 4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#else - mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t *packet = (mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t *)msgbuf; - packet->group = group; - packet->mode = mode; - mav_array_memcpy(packet->roll, roll, sizeof(int16_t)*4); - mav_array_memcpy(packet->pitch, pitch, sizeof(int16_t)*4); - mav_array_memcpy(packet->yaw, yaw, sizeof(int16_t)*4); - mav_array_memcpy(packet->thrust, thrust, sizeof(uint16_t)*4); - mav_array_memcpy(packet->led_red, led_red, sizeof(uint8_t)*4); - mav_array_memcpy(packet->led_blue, led_blue, sizeof(uint8_t)*4); - mav_array_memcpy(packet->led_green, led_green, sizeof(uint8_t)*4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST UNPACKING - - -/** - * @brief Get field group from set_quad_swarm_led_roll_pitch_yaw_thrust message - * - * @return ID of the quadrotor group (0 - 255, up to 256 groups supported) - */ -static inline uint8_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_group(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field mode from set_quad_swarm_led_roll_pitch_yaw_thrust message - * - * @return ID of the flight mode (0 - 255, up to 256 modes supported) - */ -static inline uint8_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field led_red from set_quad_swarm_led_roll_pitch_yaw_thrust message - * - * @return RGB red channel (0-255) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_red(const mavlink_message_t* msg, uint8_t *led_red) -{ - return _MAV_RETURN_uint8_t_array(msg, led_red, 4, 34); -} - -/** - * @brief Get field led_blue from set_quad_swarm_led_roll_pitch_yaw_thrust message - * - * @return RGB green channel (0-255) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_blue(const mavlink_message_t* msg, uint8_t *led_blue) -{ - return _MAV_RETURN_uint8_t_array(msg, led_blue, 4, 38); -} - -/** - * @brief Get field led_green from set_quad_swarm_led_roll_pitch_yaw_thrust message - * - * @return RGB blue channel (0-255) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_green(const mavlink_message_t* msg, uint8_t *led_green) -{ - return _MAV_RETURN_uint8_t_array(msg, led_green, 4, 42); -} - -/** - * @brief Get field roll from set_quad_swarm_led_roll_pitch_yaw_thrust message - * - * @return Desired roll angle in radians +-PI (+-INT16_MAX) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg, int16_t *roll) -{ - return _MAV_RETURN_int16_t_array(msg, roll, 4, 0); -} - -/** - * @brief Get field pitch from set_quad_swarm_led_roll_pitch_yaw_thrust message - * - * @return Desired pitch angle in radians +-PI (+-INT16_MAX) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg, int16_t *pitch) -{ - return _MAV_RETURN_int16_t_array(msg, pitch, 4, 8); -} - -/** - * @brief Get field yaw from set_quad_swarm_led_roll_pitch_yaw_thrust message - * - * @return Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg, int16_t *yaw) -{ - return _MAV_RETURN_int16_t_array(msg, yaw, 4, 16); -} - -/** - * @brief Get field thrust from set_quad_swarm_led_roll_pitch_yaw_thrust message - * - * @return Collective thrust, scaled to uint16 (0..UINT16_MAX) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg, uint16_t *thrust) -{ - return _MAV_RETURN_uint16_t_array(msg, thrust, 4, 24); -} - -/** - * @brief Decode a set_quad_swarm_led_roll_pitch_yaw_thrust message into a struct - * - * @param msg The message to decode - * @param set_quad_swarm_led_roll_pitch_yaw_thrust C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_quad_swarm_led_roll_pitch_yaw_thrust_t* set_quad_swarm_led_roll_pitch_yaw_thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_roll(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->roll); - mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_pitch(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->pitch); - mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_yaw(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->yaw); - mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_thrust(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->thrust); - set_quad_swarm_led_roll_pitch_yaw_thrust->group = mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_group(msg); - set_quad_swarm_led_roll_pitch_yaw_thrust->mode = mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_mode(msg); - mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_red(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->led_red); - mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_blue(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->led_blue); - mavlink_msg_set_quad_swarm_led_roll_pitch_yaw_thrust_get_led_green(msg, set_quad_swarm_led_roll_pitch_yaw_thrust->led_green); -#else - memcpy(set_quad_swarm_led_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h deleted file mode 100644 index 338bf0e43..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h +++ /dev/null @@ -1,324 +0,0 @@ -// MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST PACKING - -#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST 61 - -typedef struct __mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t -{ - int16_t roll[4]; ///< Desired roll angle in radians +-PI (+-INT16_MAX) - int16_t pitch[4]; ///< Desired pitch angle in radians +-PI (+-INT16_MAX) - int16_t yaw[4]; ///< Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - uint16_t thrust[4]; ///< Collective thrust, scaled to uint16 (0..UINT16_MAX) - uint8_t group; ///< ID of the quadrotor group (0 - 255, up to 256 groups supported) - uint8_t mode; ///< ID of the flight mode (0 - 255, up to 256 modes supported) -} mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t; - -#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN 34 -#define MAVLINK_MSG_ID_61_LEN 34 - -#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC 240 -#define MAVLINK_MSG_ID_61_CRC 240 - -#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_ROLL_LEN 4 -#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_PITCH_LEN 4 -#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_YAW_LEN 4 -#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_THRUST_LEN 4 - -#define MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST { \ - "SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST", \ - 6, \ - { { "roll", NULL, MAVLINK_TYPE_INT16_T, 4, 0, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_INT16_T, 4, 8, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_INT16_T, 4, 16, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, thrust) }, \ - { "group", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, group) }, \ - { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, mode) }, \ - } \ -} - - -/** - * @brief Pack a set_quad_swarm_roll_pitch_yaw_thrust message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param group ID of the quadrotor group (0 - 255, up to 256 groups supported) - * @param mode ID of the flight mode (0 - 255, up to 256 modes supported) - * @param roll Desired roll angle in radians +-PI (+-INT16_MAX) - * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX) - * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t group, uint8_t mode, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN]; - _mav_put_uint8_t(buf, 32, group); - _mav_put_uint8_t(buf, 33, mode); - _mav_put_int16_t_array(buf, 0, roll, 4); - _mav_put_int16_t_array(buf, 8, pitch, 4); - _mav_put_int16_t_array(buf, 16, yaw, 4); - _mav_put_uint16_t_array(buf, 24, thrust, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#else - mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet; - packet.group = group; - packet.mode = mode; - mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4); - mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4); - mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4); - mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#endif -} - -/** - * @brief Pack a set_quad_swarm_roll_pitch_yaw_thrust message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param group ID of the quadrotor group (0 - 255, up to 256 groups supported) - * @param mode ID of the flight mode (0 - 255, up to 256 modes supported) - * @param roll Desired roll angle in radians +-PI (+-INT16_MAX) - * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX) - * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t group,uint8_t mode,const int16_t *roll,const int16_t *pitch,const int16_t *yaw,const uint16_t *thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN]; - _mav_put_uint8_t(buf, 32, group); - _mav_put_uint8_t(buf, 33, mode); - _mav_put_int16_t_array(buf, 0, roll, 4); - _mav_put_int16_t_array(buf, 8, pitch, 4); - _mav_put_int16_t_array(buf, 16, yaw, 4); - _mav_put_uint16_t_array(buf, 24, thrust, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#else - mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet; - packet.group = group; - packet.mode = mode; - mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4); - mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4); - mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4); - mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#endif -} - -/** - * @brief Encode a set_quad_swarm_roll_pitch_yaw_thrust struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_quad_swarm_roll_pitch_yaw_thrust C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t* set_quad_swarm_roll_pitch_yaw_thrust) -{ - return mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_quad_swarm_roll_pitch_yaw_thrust->group, set_quad_swarm_roll_pitch_yaw_thrust->mode, set_quad_swarm_roll_pitch_yaw_thrust->roll, set_quad_swarm_roll_pitch_yaw_thrust->pitch, set_quad_swarm_roll_pitch_yaw_thrust->yaw, set_quad_swarm_roll_pitch_yaw_thrust->thrust); -} - -/** - * @brief Encode a set_quad_swarm_roll_pitch_yaw_thrust struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_quad_swarm_roll_pitch_yaw_thrust C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t* set_quad_swarm_roll_pitch_yaw_thrust) -{ - return mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, chan, msg, set_quad_swarm_roll_pitch_yaw_thrust->group, set_quad_swarm_roll_pitch_yaw_thrust->mode, set_quad_swarm_roll_pitch_yaw_thrust->roll, set_quad_swarm_roll_pitch_yaw_thrust->pitch, set_quad_swarm_roll_pitch_yaw_thrust->yaw, set_quad_swarm_roll_pitch_yaw_thrust->thrust); -} - -/** - * @brief Send a set_quad_swarm_roll_pitch_yaw_thrust message - * @param chan MAVLink channel to send the message - * - * @param group ID of the quadrotor group (0 - 255, up to 256 groups supported) - * @param mode ID of the flight mode (0 - 255, up to 256 modes supported) - * @param roll Desired roll angle in radians +-PI (+-INT16_MAX) - * @param pitch Desired pitch angle in radians +-PI (+-INT16_MAX) - * @param yaw Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - * @param thrust Collective thrust, scaled to uint16 (0..UINT16_MAX) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t group, uint8_t mode, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN]; - _mav_put_uint8_t(buf, 32, group); - _mav_put_uint8_t(buf, 33, mode); - _mav_put_int16_t_array(buf, 0, roll, 4); - _mav_put_int16_t_array(buf, 8, pitch, 4); - _mav_put_int16_t_array(buf, 16, yaw, 4); - _mav_put_uint16_t_array(buf, 24, thrust, 4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#else - mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet; - packet.group = group; - packet.mode = mode; - mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*4); - mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*4); - mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*4); - mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t group, uint8_t mode, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 32, group); - _mav_put_uint8_t(buf, 33, mode); - _mav_put_int16_t_array(buf, 0, roll, 4); - _mav_put_int16_t_array(buf, 8, pitch, 4); - _mav_put_int16_t_array(buf, 16, yaw, 4); - _mav_put_uint16_t_array(buf, 24, thrust, 4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#else - mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t *packet = (mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t *)msgbuf; - packet->group = group; - packet->mode = mode; - mav_array_memcpy(packet->roll, roll, sizeof(int16_t)*4); - mav_array_memcpy(packet->pitch, pitch, sizeof(int16_t)*4); - mav_array_memcpy(packet->yaw, yaw, sizeof(int16_t)*4); - mav_array_memcpy(packet->thrust, thrust, sizeof(uint16_t)*4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST UNPACKING - - -/** - * @brief Get field group from set_quad_swarm_roll_pitch_yaw_thrust message - * - * @return ID of the quadrotor group (0 - 255, up to 256 groups supported) - */ -static inline uint8_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_group(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field mode from set_quad_swarm_roll_pitch_yaw_thrust message - * - * @return ID of the flight mode (0 - 255, up to 256 modes supported) - */ -static inline uint8_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 33); -} - -/** - * @brief Get field roll from set_quad_swarm_roll_pitch_yaw_thrust message - * - * @return Desired roll angle in radians +-PI (+-INT16_MAX) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg, int16_t *roll) -{ - return _MAV_RETURN_int16_t_array(msg, roll, 4, 0); -} - -/** - * @brief Get field pitch from set_quad_swarm_roll_pitch_yaw_thrust message - * - * @return Desired pitch angle in radians +-PI (+-INT16_MAX) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg, int16_t *pitch) -{ - return _MAV_RETURN_int16_t_array(msg, pitch, 4, 8); -} - -/** - * @brief Get field yaw from set_quad_swarm_roll_pitch_yaw_thrust message - * - * @return Desired yaw angle in radians, scaled to int16 +-PI (+-INT16_MAX) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg, int16_t *yaw) -{ - return _MAV_RETURN_int16_t_array(msg, yaw, 4, 16); -} - -/** - * @brief Get field thrust from set_quad_swarm_roll_pitch_yaw_thrust message - * - * @return Collective thrust, scaled to uint16 (0..UINT16_MAX) - */ -static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg, uint16_t *thrust) -{ - return _MAV_RETURN_uint16_t_array(msg, thrust, 4, 24); -} - -/** - * @brief Decode a set_quad_swarm_roll_pitch_yaw_thrust message into a struct - * - * @param msg The message to decode - * @param set_quad_swarm_roll_pitch_yaw_thrust C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t* set_quad_swarm_roll_pitch_yaw_thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_roll(msg, set_quad_swarm_roll_pitch_yaw_thrust->roll); - mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitch(msg, set_quad_swarm_roll_pitch_yaw_thrust->pitch); - mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(msg, set_quad_swarm_roll_pitch_yaw_thrust->yaw); - mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_thrust(msg, set_quad_swarm_roll_pitch_yaw_thrust->thrust); - set_quad_swarm_roll_pitch_yaw_thrust->group = mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_group(msg); - set_quad_swarm_roll_pitch_yaw_thrust->mode = mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_mode(msg); -#else - memcpy(set_quad_swarm_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h deleted file mode 100644 index 4d0e5931f..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST PACKING - -#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 57 - -typedef struct __mavlink_set_roll_pitch_yaw_speed_thrust_t -{ - float roll_speed; ///< Desired roll angular speed in rad/s - float pitch_speed; ///< Desired pitch angular speed in rad/s - float yaw_speed; ///< Desired yaw angular speed in rad/s - float thrust; ///< Collective thrust, normalized to 0 .. 1 - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_set_roll_pitch_yaw_speed_thrust_t; - -#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN 18 -#define MAVLINK_MSG_ID_57_LEN 18 - -#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC 24 -#define MAVLINK_MSG_ID_57_CRC 24 - - - -#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST { \ - "SET_ROLL_PITCH_YAW_SPEED_THRUST", \ - 6, \ - { { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, roll_speed) }, \ - { "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, pitch_speed) }, \ - { "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, yaw_speed) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, thrust) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a set_roll_pitch_yaw_speed_thrust message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param roll_speed Desired roll angular speed in rad/s - * @param pitch_speed Desired pitch angular speed in rad/s - * @param yaw_speed Desired yaw angular speed in rad/s - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN]; - _mav_put_float(buf, 0, roll_speed); - _mav_put_float(buf, 4, pitch_speed); - _mav_put_float(buf, 8, yaw_speed); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#else - mavlink_set_roll_pitch_yaw_speed_thrust_t packet; - packet.roll_speed = roll_speed; - packet.pitch_speed = pitch_speed; - packet.yaw_speed = yaw_speed; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#endif -} - -/** - * @brief Pack a set_roll_pitch_yaw_speed_thrust message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param roll_speed Desired roll angular speed in rad/s - * @param pitch_speed Desired pitch angular speed in rad/s - * @param yaw_speed Desired yaw angular speed in rad/s - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,float roll_speed,float pitch_speed,float yaw_speed,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN]; - _mav_put_float(buf, 0, roll_speed); - _mav_put_float(buf, 4, pitch_speed); - _mav_put_float(buf, 8, yaw_speed); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#else - mavlink_set_roll_pitch_yaw_speed_thrust_t packet; - packet.roll_speed = roll_speed; - packet.pitch_speed = pitch_speed; - packet.yaw_speed = yaw_speed; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#endif -} - -/** - * @brief Encode a set_roll_pitch_yaw_speed_thrust struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_roll_pitch_yaw_speed_thrust C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust) -{ - return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust); -} - -/** - * @brief Encode a set_roll_pitch_yaw_speed_thrust struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_roll_pitch_yaw_speed_thrust C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust) -{ - return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(system_id, component_id, chan, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust); -} - -/** - * @brief Send a set_roll_pitch_yaw_speed_thrust message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param roll_speed Desired roll angular speed in rad/s - * @param pitch_speed Desired pitch angular speed in rad/s - * @param yaw_speed Desired yaw angular speed in rad/s - * @param thrust Collective thrust, normalized to 0 .. 1 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN]; - _mav_put_float(buf, 0, roll_speed); - _mav_put_float(buf, 4, pitch_speed); - _mav_put_float(buf, 8, yaw_speed); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#endif -#else - mavlink_set_roll_pitch_yaw_speed_thrust_t packet; - packet.roll_speed = roll_speed; - packet.pitch_speed = pitch_speed; - packet.yaw_speed = yaw_speed; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, roll_speed); - _mav_put_float(buf, 4, pitch_speed); - _mav_put_float(buf, 8, yaw_speed); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#endif -#else - mavlink_set_roll_pitch_yaw_speed_thrust_t *packet = (mavlink_set_roll_pitch_yaw_speed_thrust_t *)msgbuf; - packet->roll_speed = roll_speed; - packet->pitch_speed = pitch_speed; - packet->yaw_speed = yaw_speed; - packet->thrust = thrust; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST UNPACKING - - -/** - * @brief Get field target_system from set_roll_pitch_yaw_speed_thrust message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from set_roll_pitch_yaw_speed_thrust message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field roll_speed from set_roll_pitch_yaw_speed_thrust message - * - * @return Desired roll angular speed in rad/s - */ -static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field pitch_speed from set_roll_pitch_yaw_speed_thrust message - * - * @return Desired pitch angular speed in rad/s - */ -static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field yaw_speed from set_roll_pitch_yaw_speed_thrust message - * - * @return Desired yaw angular speed in rad/s - */ -static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field thrust from set_roll_pitch_yaw_speed_thrust message - * - * @return Collective thrust, normalized to 0 .. 1 - */ -static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a set_roll_pitch_yaw_speed_thrust message into a struct - * - * @param msg The message to decode - * @param set_roll_pitch_yaw_speed_thrust C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_roll_pitch_yaw_speed_thrust->roll_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(msg); - set_roll_pitch_yaw_speed_thrust->pitch_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(msg); - set_roll_pitch_yaw_speed_thrust->yaw_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(msg); - set_roll_pitch_yaw_speed_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(msg); - set_roll_pitch_yaw_speed_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(msg); - set_roll_pitch_yaw_speed_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(msg); -#else - memcpy(set_roll_pitch_yaw_speed_thrust, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h deleted file mode 100644 index 21e0a43f2..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE SET_ROLL_PITCH_YAW_THRUST PACKING - -#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 56 - -typedef struct __mavlink_set_roll_pitch_yaw_thrust_t -{ - float roll; ///< Desired roll angle in radians - float pitch; ///< Desired pitch angle in radians - float yaw; ///< Desired yaw angle in radians - float thrust; ///< Collective thrust, normalized to 0 .. 1 - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_set_roll_pitch_yaw_thrust_t; - -#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN 18 -#define MAVLINK_MSG_ID_56_LEN 18 - -#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC 100 -#define MAVLINK_MSG_ID_56_CRC 100 - - - -#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST { \ - "SET_ROLL_PITCH_YAW_THRUST", \ - 6, \ - { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, thrust) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a set_roll_pitch_yaw_thrust message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param roll Desired roll angle in radians - * @param pitch Desired pitch angle in radians - * @param yaw Desired yaw angle in radians - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#else - mavlink_set_roll_pitch_yaw_thrust_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#endif -} - -/** - * @brief Pack a set_roll_pitch_yaw_thrust message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param roll Desired roll angle in radians - * @param pitch Desired pitch angle in radians - * @param yaw Desired yaw angle in radians - * @param thrust Collective thrust, normalized to 0 .. 1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,float roll,float pitch,float yaw,float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#else - mavlink_set_roll_pitch_yaw_thrust_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#endif -} - -/** - * @brief Encode a set_roll_pitch_yaw_thrust struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_roll_pitch_yaw_thrust C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust) -{ - return mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust); -} - -/** - * @brief Encode a set_roll_pitch_yaw_thrust struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_roll_pitch_yaw_thrust C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust) -{ - return mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, chan, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust); -} - -/** - * @brief Send a set_roll_pitch_yaw_thrust message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param roll Desired roll angle in radians - * @param pitch Desired pitch angle in radians - * @param yaw Desired yaw angle in radians - * @param thrust Collective thrust, normalized to 0 .. 1 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#else - mavlink_set_roll_pitch_yaw_thrust_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)&packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#else - mavlink_set_roll_pitch_yaw_thrust_t *packet = (mavlink_set_roll_pitch_yaw_thrust_t *)msgbuf; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->thrust = thrust; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)packet, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_ROLL_PITCH_YAW_THRUST UNPACKING - - -/** - * @brief Get field target_system from set_roll_pitch_yaw_thrust message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from set_roll_pitch_yaw_thrust message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field roll from set_roll_pitch_yaw_thrust message - * - * @return Desired roll angle in radians - */ -static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field pitch from set_roll_pitch_yaw_thrust message - * - * @return Desired pitch angle in radians - */ -static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field yaw from set_roll_pitch_yaw_thrust message - * - * @return Desired yaw angle in radians - */ -static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field thrust from set_roll_pitch_yaw_thrust message - * - * @return Collective thrust, normalized to 0 .. 1 - */ -static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a set_roll_pitch_yaw_thrust message into a struct - * - * @param msg The message to decode - * @param set_roll_pitch_yaw_thrust C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_roll_pitch_yaw_thrust->roll = mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(msg); - set_roll_pitch_yaw_thrust->pitch = mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(msg); - set_roll_pitch_yaw_thrust->yaw = mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(msg); - set_roll_pitch_yaw_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(msg); - set_roll_pitch_yaw_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(msg); - set_roll_pitch_yaw_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(msg); -#else - memcpy(set_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h deleted file mode 100644 index 90b63427b..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_6dof.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE SETPOINT_6DOF PACKING - -#define MAVLINK_MSG_ID_SETPOINT_6DOF 149 - -typedef struct __mavlink_setpoint_6dof_t -{ - float trans_x; ///< Translational Component in x - float trans_y; ///< Translational Component in y - float trans_z; ///< Translational Component in z - float rot_x; ///< Rotational Component in x - float rot_y; ///< Rotational Component in y - float rot_z; ///< Rotational Component in z - uint8_t target_system; ///< System ID -} mavlink_setpoint_6dof_t; - -#define MAVLINK_MSG_ID_SETPOINT_6DOF_LEN 25 -#define MAVLINK_MSG_ID_149_LEN 25 - -#define MAVLINK_MSG_ID_SETPOINT_6DOF_CRC 15 -#define MAVLINK_MSG_ID_149_CRC 15 - - - -#define MAVLINK_MESSAGE_INFO_SETPOINT_6DOF { \ - "SETPOINT_6DOF", \ - 7, \ - { { "trans_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_setpoint_6dof_t, trans_x) }, \ - { "trans_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_setpoint_6dof_t, trans_y) }, \ - { "trans_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_setpoint_6dof_t, trans_z) }, \ - { "rot_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_setpoint_6dof_t, rot_x) }, \ - { "rot_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_setpoint_6dof_t, rot_y) }, \ - { "rot_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_setpoint_6dof_t, rot_z) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_setpoint_6dof_t, target_system) }, \ - } \ -} - - -/** - * @brief Pack a setpoint_6dof message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param trans_x Translational Component in x - * @param trans_y Translational Component in y - * @param trans_z Translational Component in z - * @param rot_x Rotational Component in x - * @param rot_y Rotational Component in y - * @param rot_z Rotational Component in z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_setpoint_6dof_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETPOINT_6DOF_LEN]; - _mav_put_float(buf, 0, trans_x); - _mav_put_float(buf, 4, trans_y); - _mav_put_float(buf, 8, trans_z); - _mav_put_float(buf, 12, rot_x); - _mav_put_float(buf, 16, rot_y); - _mav_put_float(buf, 20, rot_z); - _mav_put_uint8_t(buf, 24, target_system); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#else - mavlink_setpoint_6dof_t packet; - packet.trans_x = trans_x; - packet.trans_y = trans_y; - packet.trans_z = trans_z; - packet.rot_x = rot_x; - packet.rot_y = rot_y; - packet.rot_z = rot_z; - packet.target_system = target_system; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SETPOINT_6DOF; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#endif -} - -/** - * @brief Pack a setpoint_6dof message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param trans_x Translational Component in x - * @param trans_y Translational Component in y - * @param trans_z Translational Component in z - * @param rot_x Rotational Component in x - * @param rot_y Rotational Component in y - * @param rot_z Rotational Component in z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_setpoint_6dof_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,float trans_x,float trans_y,float trans_z,float rot_x,float rot_y,float rot_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETPOINT_6DOF_LEN]; - _mav_put_float(buf, 0, trans_x); - _mav_put_float(buf, 4, trans_y); - _mav_put_float(buf, 8, trans_z); - _mav_put_float(buf, 12, rot_x); - _mav_put_float(buf, 16, rot_y); - _mav_put_float(buf, 20, rot_z); - _mav_put_uint8_t(buf, 24, target_system); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#else - mavlink_setpoint_6dof_t packet; - packet.trans_x = trans_x; - packet.trans_y = trans_y; - packet.trans_z = trans_z; - packet.rot_x = rot_x; - packet.rot_y = rot_y; - packet.rot_z = rot_z; - packet.target_system = target_system; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SETPOINT_6DOF; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#endif -} - -/** - * @brief Encode a setpoint_6dof struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param setpoint_6dof C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_setpoint_6dof_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_setpoint_6dof_t* setpoint_6dof) -{ - return mavlink_msg_setpoint_6dof_pack(system_id, component_id, msg, setpoint_6dof->target_system, setpoint_6dof->trans_x, setpoint_6dof->trans_y, setpoint_6dof->trans_z, setpoint_6dof->rot_x, setpoint_6dof->rot_y, setpoint_6dof->rot_z); -} - -/** - * @brief Encode a setpoint_6dof struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param setpoint_6dof C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_setpoint_6dof_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_setpoint_6dof_t* setpoint_6dof) -{ - return mavlink_msg_setpoint_6dof_pack_chan(system_id, component_id, chan, msg, setpoint_6dof->target_system, setpoint_6dof->trans_x, setpoint_6dof->trans_y, setpoint_6dof->trans_z, setpoint_6dof->rot_x, setpoint_6dof->rot_y, setpoint_6dof->rot_z); -} - -/** - * @brief Send a setpoint_6dof message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param trans_x Translational Component in x - * @param trans_y Translational Component in y - * @param trans_z Translational Component in z - * @param rot_x Rotational Component in x - * @param rot_y Rotational Component in y - * @param rot_z Rotational Component in z - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_setpoint_6dof_send(mavlink_channel_t chan, uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETPOINT_6DOF_LEN]; - _mav_put_float(buf, 0, trans_x); - _mav_put_float(buf, 4, trans_y); - _mav_put_float(buf, 8, trans_z); - _mav_put_float(buf, 12, rot_x); - _mav_put_float(buf, 16, rot_y); - _mav_put_float(buf, 20, rot_z); - _mav_put_uint8_t(buf, 24, target_system); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#endif -#else - mavlink_setpoint_6dof_t packet; - packet.trans_x = trans_x; - packet.trans_y = trans_y; - packet.trans_z = trans_z; - packet.rot_x = rot_x; - packet.rot_y = rot_y; - packet.rot_z = rot_z; - packet.target_system = target_system; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SETPOINT_6DOF_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_setpoint_6dof_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, float trans_x, float trans_y, float trans_z, float rot_x, float rot_y, float rot_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, trans_x); - _mav_put_float(buf, 4, trans_y); - _mav_put_float(buf, 8, trans_z); - _mav_put_float(buf, 12, rot_x); - _mav_put_float(buf, 16, rot_y); - _mav_put_float(buf, 20, rot_z); - _mav_put_uint8_t(buf, 24, target_system); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, buf, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#endif -#else - mavlink_setpoint_6dof_t *packet = (mavlink_setpoint_6dof_t *)msgbuf; - packet->trans_x = trans_x; - packet->trans_y = trans_y; - packet->trans_z = trans_z; - packet->rot_x = rot_x; - packet->rot_y = rot_y; - packet->rot_z = rot_z; - packet->target_system = target_system; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN, MAVLINK_MSG_ID_SETPOINT_6DOF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_6DOF, (const char *)packet, MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SETPOINT_6DOF UNPACKING - - -/** - * @brief Get field target_system from setpoint_6dof message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_setpoint_6dof_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 24); -} - -/** - * @brief Get field trans_x from setpoint_6dof message - * - * @return Translational Component in x - */ -static inline float mavlink_msg_setpoint_6dof_get_trans_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field trans_y from setpoint_6dof message - * - * @return Translational Component in y - */ -static inline float mavlink_msg_setpoint_6dof_get_trans_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field trans_z from setpoint_6dof message - * - * @return Translational Component in z - */ -static inline float mavlink_msg_setpoint_6dof_get_trans_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field rot_x from setpoint_6dof message - * - * @return Rotational Component in x - */ -static inline float mavlink_msg_setpoint_6dof_get_rot_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field rot_y from setpoint_6dof message - * - * @return Rotational Component in y - */ -static inline float mavlink_msg_setpoint_6dof_get_rot_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field rot_z from setpoint_6dof message - * - * @return Rotational Component in z - */ -static inline float mavlink_msg_setpoint_6dof_get_rot_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a setpoint_6dof message into a struct - * - * @param msg The message to decode - * @param setpoint_6dof C-struct to decode the message contents into - */ -static inline void mavlink_msg_setpoint_6dof_decode(const mavlink_message_t* msg, mavlink_setpoint_6dof_t* setpoint_6dof) -{ -#if MAVLINK_NEED_BYTE_SWAP - setpoint_6dof->trans_x = mavlink_msg_setpoint_6dof_get_trans_x(msg); - setpoint_6dof->trans_y = mavlink_msg_setpoint_6dof_get_trans_y(msg); - setpoint_6dof->trans_z = mavlink_msg_setpoint_6dof_get_trans_z(msg); - setpoint_6dof->rot_x = mavlink_msg_setpoint_6dof_get_rot_x(msg); - setpoint_6dof->rot_y = mavlink_msg_setpoint_6dof_get_rot_y(msg); - setpoint_6dof->rot_z = mavlink_msg_setpoint_6dof_get_rot_z(msg); - setpoint_6dof->target_system = mavlink_msg_setpoint_6dof_get_target_system(msg); -#else - memcpy(setpoint_6dof, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SETPOINT_6DOF_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h deleted file mode 100644 index 308a211cd..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_setpoint_8dof.h +++ /dev/null @@ -1,401 +0,0 @@ -// MESSAGE SETPOINT_8DOF PACKING - -#define MAVLINK_MSG_ID_SETPOINT_8DOF 148 - -typedef struct __mavlink_setpoint_8dof_t -{ - float val1; ///< Value 1 - float val2; ///< Value 2 - float val3; ///< Value 3 - float val4; ///< Value 4 - float val5; ///< Value 5 - float val6; ///< Value 6 - float val7; ///< Value 7 - float val8; ///< Value 8 - uint8_t target_system; ///< System ID -} mavlink_setpoint_8dof_t; - -#define MAVLINK_MSG_ID_SETPOINT_8DOF_LEN 33 -#define MAVLINK_MSG_ID_148_LEN 33 - -#define MAVLINK_MSG_ID_SETPOINT_8DOF_CRC 241 -#define MAVLINK_MSG_ID_148_CRC 241 - - - -#define MAVLINK_MESSAGE_INFO_SETPOINT_8DOF { \ - "SETPOINT_8DOF", \ - 9, \ - { { "val1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_setpoint_8dof_t, val1) }, \ - { "val2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_setpoint_8dof_t, val2) }, \ - { "val3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_setpoint_8dof_t, val3) }, \ - { "val4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_setpoint_8dof_t, val4) }, \ - { "val5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_setpoint_8dof_t, val5) }, \ - { "val6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_setpoint_8dof_t, val6) }, \ - { "val7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_setpoint_8dof_t, val7) }, \ - { "val8", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_setpoint_8dof_t, val8) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_setpoint_8dof_t, target_system) }, \ - } \ -} - - -/** - * @brief Pack a setpoint_8dof message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param val1 Value 1 - * @param val2 Value 2 - * @param val3 Value 3 - * @param val4 Value 4 - * @param val5 Value 5 - * @param val6 Value 6 - * @param val7 Value 7 - * @param val8 Value 8 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_setpoint_8dof_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETPOINT_8DOF_LEN]; - _mav_put_float(buf, 0, val1); - _mav_put_float(buf, 4, val2); - _mav_put_float(buf, 8, val3); - _mav_put_float(buf, 12, val4); - _mav_put_float(buf, 16, val5); - _mav_put_float(buf, 20, val6); - _mav_put_float(buf, 24, val7); - _mav_put_float(buf, 28, val8); - _mav_put_uint8_t(buf, 32, target_system); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#else - mavlink_setpoint_8dof_t packet; - packet.val1 = val1; - packet.val2 = val2; - packet.val3 = val3; - packet.val4 = val4; - packet.val5 = val5; - packet.val6 = val6; - packet.val7 = val7; - packet.val8 = val8; - packet.target_system = target_system; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SETPOINT_8DOF; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#endif -} - -/** - * @brief Pack a setpoint_8dof message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param val1 Value 1 - * @param val2 Value 2 - * @param val3 Value 3 - * @param val4 Value 4 - * @param val5 Value 5 - * @param val6 Value 6 - * @param val7 Value 7 - * @param val8 Value 8 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_setpoint_8dof_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,float val1,float val2,float val3,float val4,float val5,float val6,float val7,float val8) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETPOINT_8DOF_LEN]; - _mav_put_float(buf, 0, val1); - _mav_put_float(buf, 4, val2); - _mav_put_float(buf, 8, val3); - _mav_put_float(buf, 12, val4); - _mav_put_float(buf, 16, val5); - _mav_put_float(buf, 20, val6); - _mav_put_float(buf, 24, val7); - _mav_put_float(buf, 28, val8); - _mav_put_uint8_t(buf, 32, target_system); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#else - mavlink_setpoint_8dof_t packet; - packet.val1 = val1; - packet.val2 = val2; - packet.val3 = val3; - packet.val4 = val4; - packet.val5 = val5; - packet.val6 = val6; - packet.val7 = val7; - packet.val8 = val8; - packet.target_system = target_system; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SETPOINT_8DOF; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#endif -} - -/** - * @brief Encode a setpoint_8dof struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param setpoint_8dof C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_setpoint_8dof_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_setpoint_8dof_t* setpoint_8dof) -{ - return mavlink_msg_setpoint_8dof_pack(system_id, component_id, msg, setpoint_8dof->target_system, setpoint_8dof->val1, setpoint_8dof->val2, setpoint_8dof->val3, setpoint_8dof->val4, setpoint_8dof->val5, setpoint_8dof->val6, setpoint_8dof->val7, setpoint_8dof->val8); -} - -/** - * @brief Encode a setpoint_8dof struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param setpoint_8dof C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_setpoint_8dof_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_setpoint_8dof_t* setpoint_8dof) -{ - return mavlink_msg_setpoint_8dof_pack_chan(system_id, component_id, chan, msg, setpoint_8dof->target_system, setpoint_8dof->val1, setpoint_8dof->val2, setpoint_8dof->val3, setpoint_8dof->val4, setpoint_8dof->val5, setpoint_8dof->val6, setpoint_8dof->val7, setpoint_8dof->val8); -} - -/** - * @brief Send a setpoint_8dof message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param val1 Value 1 - * @param val2 Value 2 - * @param val3 Value 3 - * @param val4 Value 4 - * @param val5 Value 5 - * @param val6 Value 6 - * @param val7 Value 7 - * @param val8 Value 8 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_setpoint_8dof_send(mavlink_channel_t chan, uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SETPOINT_8DOF_LEN]; - _mav_put_float(buf, 0, val1); - _mav_put_float(buf, 4, val2); - _mav_put_float(buf, 8, val3); - _mav_put_float(buf, 12, val4); - _mav_put_float(buf, 16, val5); - _mav_put_float(buf, 20, val6); - _mav_put_float(buf, 24, val7); - _mav_put_float(buf, 28, val8); - _mav_put_uint8_t(buf, 32, target_system); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#endif -#else - mavlink_setpoint_8dof_t packet; - packet.val1 = val1; - packet.val2 = val2; - packet.val3 = val3; - packet.val4 = val4; - packet.val5 = val5; - packet.val6 = val6; - packet.val7 = val7; - packet.val8 = val8; - packet.target_system = target_system; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)&packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SETPOINT_8DOF_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_setpoint_8dof_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, float val1, float val2, float val3, float val4, float val5, float val6, float val7, float val8) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, val1); - _mav_put_float(buf, 4, val2); - _mav_put_float(buf, 8, val3); - _mav_put_float(buf, 12, val4); - _mav_put_float(buf, 16, val5); - _mav_put_float(buf, 20, val6); - _mav_put_float(buf, 24, val7); - _mav_put_float(buf, 28, val8); - _mav_put_uint8_t(buf, 32, target_system); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, buf, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#endif -#else - mavlink_setpoint_8dof_t *packet = (mavlink_setpoint_8dof_t *)msgbuf; - packet->val1 = val1; - packet->val2 = val2; - packet->val3 = val3; - packet->val4 = val4; - packet->val5 = val5; - packet->val6 = val6; - packet->val7 = val7; - packet->val8 = val8; - packet->target_system = target_system; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN, MAVLINK_MSG_ID_SETPOINT_8DOF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SETPOINT_8DOF, (const char *)packet, MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SETPOINT_8DOF UNPACKING - - -/** - * @brief Get field target_system from setpoint_8dof message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_setpoint_8dof_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 32); -} - -/** - * @brief Get field val1 from setpoint_8dof message - * - * @return Value 1 - */ -static inline float mavlink_msg_setpoint_8dof_get_val1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field val2 from setpoint_8dof message - * - * @return Value 2 - */ -static inline float mavlink_msg_setpoint_8dof_get_val2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field val3 from setpoint_8dof message - * - * @return Value 3 - */ -static inline float mavlink_msg_setpoint_8dof_get_val3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field val4 from setpoint_8dof message - * - * @return Value 4 - */ -static inline float mavlink_msg_setpoint_8dof_get_val4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field val5 from setpoint_8dof message - * - * @return Value 5 - */ -static inline float mavlink_msg_setpoint_8dof_get_val5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field val6 from setpoint_8dof message - * - * @return Value 6 - */ -static inline float mavlink_msg_setpoint_8dof_get_val6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field val7 from setpoint_8dof message - * - * @return Value 7 - */ -static inline float mavlink_msg_setpoint_8dof_get_val7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field val8 from setpoint_8dof message - * - * @return Value 8 - */ -static inline float mavlink_msg_setpoint_8dof_get_val8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a setpoint_8dof message into a struct - * - * @param msg The message to decode - * @param setpoint_8dof C-struct to decode the message contents into - */ -static inline void mavlink_msg_setpoint_8dof_decode(const mavlink_message_t* msg, mavlink_setpoint_8dof_t* setpoint_8dof) -{ -#if MAVLINK_NEED_BYTE_SWAP - setpoint_8dof->val1 = mavlink_msg_setpoint_8dof_get_val1(msg); - setpoint_8dof->val2 = mavlink_msg_setpoint_8dof_get_val2(msg); - setpoint_8dof->val3 = mavlink_msg_setpoint_8dof_get_val3(msg); - setpoint_8dof->val4 = mavlink_msg_setpoint_8dof_get_val4(msg); - setpoint_8dof->val5 = mavlink_msg_setpoint_8dof_get_val5(msg); - setpoint_8dof->val6 = mavlink_msg_setpoint_8dof_get_val6(msg); - setpoint_8dof->val7 = mavlink_msg_setpoint_8dof_get_val7(msg); - setpoint_8dof->val8 = mavlink_msg_setpoint_8dof_get_val8(msg); - setpoint_8dof->target_system = mavlink_msg_setpoint_8dof_get_target_system(msg); -#else - memcpy(setpoint_8dof, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SETPOINT_8DOF_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h deleted file mode 100644 index db3a92642..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sim_state.h +++ /dev/null @@ -1,689 +0,0 @@ -// MESSAGE SIM_STATE PACKING - -#define MAVLINK_MSG_ID_SIM_STATE 108 - -typedef struct __mavlink_sim_state_t -{ - float q1; ///< True attitude quaternion component 1 - float q2; ///< True attitude quaternion component 2 - float q3; ///< True attitude quaternion component 3 - float q4; ///< True attitude quaternion component 4 - float roll; ///< Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - float pitch; ///< Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - float yaw; ///< Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - float xacc; ///< X acceleration m/s/s - float yacc; ///< Y acceleration m/s/s - float zacc; ///< Z acceleration m/s/s - float xgyro; ///< Angular speed around X axis rad/s - float ygyro; ///< Angular speed around Y axis rad/s - float zgyro; ///< Angular speed around Z axis rad/s - float lat; ///< Latitude in degrees - float lon; ///< Longitude in degrees - float alt; ///< Altitude in meters - float std_dev_horz; ///< Horizontal position standard deviation - float std_dev_vert; ///< Vertical position standard deviation - float vn; ///< True velocity in m/s in NORTH direction in earth-fixed NED frame - float ve; ///< True velocity in m/s in EAST direction in earth-fixed NED frame - float vd; ///< True velocity in m/s in DOWN direction in earth-fixed NED frame -} mavlink_sim_state_t; - -#define MAVLINK_MSG_ID_SIM_STATE_LEN 84 -#define MAVLINK_MSG_ID_108_LEN 84 - -#define MAVLINK_MSG_ID_SIM_STATE_CRC 32 -#define MAVLINK_MSG_ID_108_CRC 32 - - - -#define MAVLINK_MESSAGE_INFO_SIM_STATE { \ - "SIM_STATE", \ - 21, \ - { { "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sim_state_t, q1) }, \ - { "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_sim_state_t, q2) }, \ - { "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_sim_state_t, q3) }, \ - { "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sim_state_t, q4) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sim_state_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sim_state_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sim_state_t, yaw) }, \ - { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sim_state_t, xacc) }, \ - { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sim_state_t, yacc) }, \ - { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_sim_state_t, zacc) }, \ - { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_sim_state_t, xgyro) }, \ - { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_sim_state_t, ygyro) }, \ - { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_sim_state_t, zgyro) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_sim_state_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_sim_state_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_sim_state_t, alt) }, \ - { "std_dev_horz", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_sim_state_t, std_dev_horz) }, \ - { "std_dev_vert", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_sim_state_t, std_dev_vert) }, \ - { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_sim_state_t, vn) }, \ - { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_sim_state_t, ve) }, \ - { "vd", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_sim_state_t, vd) }, \ - } \ -} - - -/** - * @brief Pack a sim_state message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param q1 True attitude quaternion component 1 - * @param q2 True attitude quaternion component 2 - * @param q3 True attitude quaternion component 3 - * @param q4 True attitude quaternion component 4 - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sim_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _mav_put_float(buf, 28, xacc); - _mav_put_float(buf, 32, yacc); - _mav_put_float(buf, 36, zacc); - _mav_put_float(buf, 40, xgyro); - _mav_put_float(buf, 44, ygyro); - _mav_put_float(buf, 48, zgyro); - _mav_put_float(buf, 52, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIM_STATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif -} - -/** - * @brief Pack a sim_state message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param q1 True attitude quaternion component 1 - * @param q2 True attitude quaternion component 2 - * @param q3 True attitude quaternion component 3 - * @param q4 True attitude quaternion component 4 - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sim_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float q1,float q2,float q3,float q4,float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float lat,float lon,float alt,float std_dev_horz,float std_dev_vert,float vn,float ve,float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _mav_put_float(buf, 28, xacc); - _mav_put_float(buf, 32, yacc); - _mav_put_float(buf, 36, zacc); - _mav_put_float(buf, 40, xgyro); - _mav_put_float(buf, 44, ygyro); - _mav_put_float(buf, 48, zgyro); - _mav_put_float(buf, 52, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SIM_STATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif -} - -/** - * @brief Encode a sim_state struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param sim_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sim_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) -{ - return mavlink_msg_sim_state_pack(system_id, component_id, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); -} - -/** - * @brief Encode a sim_state struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sim_state C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sim_state_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sim_state_t* sim_state) -{ - return mavlink_msg_sim_state_pack_chan(system_id, component_id, chan, msg, sim_state->q1, sim_state->q2, sim_state->q3, sim_state->q4, sim_state->roll, sim_state->pitch, sim_state->yaw, sim_state->xacc, sim_state->yacc, sim_state->zacc, sim_state->xgyro, sim_state->ygyro, sim_state->zgyro, sim_state->lat, sim_state->lon, sim_state->alt, sim_state->std_dev_horz, sim_state->std_dev_vert, sim_state->vn, sim_state->ve, sim_state->vd); -} - -/** - * @brief Send a sim_state message - * @param chan MAVLink channel to send the message - * - * @param q1 True attitude quaternion component 1 - * @param q2 True attitude quaternion component 2 - * @param q3 True attitude quaternion component 3 - * @param q4 True attitude quaternion component 4 - * @param roll Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - * @param pitch Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - * @param yaw Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - * @param xacc X acceleration m/s/s - * @param yacc Y acceleration m/s/s - * @param zacc Z acceleration m/s/s - * @param xgyro Angular speed around X axis rad/s - * @param ygyro Angular speed around Y axis rad/s - * @param zgyro Angular speed around Z axis rad/s - * @param lat Latitude in degrees - * @param lon Longitude in degrees - * @param alt Altitude in meters - * @param std_dev_horz Horizontal position standard deviation - * @param std_dev_vert Vertical position standard deviation - * @param vn True velocity in m/s in NORTH direction in earth-fixed NED frame - * @param ve True velocity in m/s in EAST direction in earth-fixed NED frame - * @param vd True velocity in m/s in DOWN direction in earth-fixed NED frame - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_sim_state_send(mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SIM_STATE_LEN]; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _mav_put_float(buf, 28, xacc); - _mav_put_float(buf, 32, yacc); - _mav_put_float(buf, 36, zacc); - _mav_put_float(buf, 40, xgyro); - _mav_put_float(buf, 44, ygyro); - _mav_put_float(buf, 48, zgyro); - _mav_put_float(buf, 52, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif -#else - mavlink_sim_state_t packet; - packet.q1 = q1; - packet.q2 = q2; - packet.q3 = q3; - packet.q4 = q4; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.xacc = xacc; - packet.yacc = yacc; - packet.zacc = zacc; - packet.xgyro = xgyro; - packet.ygyro = ygyro; - packet.zgyro = zgyro; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.std_dev_horz = std_dev_horz; - packet.std_dev_vert = std_dev_vert; - packet.vn = vn; - packet.ve = ve; - packet.vd = vd; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)&packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SIM_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sim_state_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float q1, float q2, float q3, float q4, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float lat, float lon, float alt, float std_dev_horz, float std_dev_vert, float vn, float ve, float vd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, q1); - _mav_put_float(buf, 4, q2); - _mav_put_float(buf, 8, q3); - _mav_put_float(buf, 12, q4); - _mav_put_float(buf, 16, roll); - _mav_put_float(buf, 20, pitch); - _mav_put_float(buf, 24, yaw); - _mav_put_float(buf, 28, xacc); - _mav_put_float(buf, 32, yacc); - _mav_put_float(buf, 36, zacc); - _mav_put_float(buf, 40, xgyro); - _mav_put_float(buf, 44, ygyro); - _mav_put_float(buf, 48, zgyro); - _mav_put_float(buf, 52, lat); - _mav_put_float(buf, 56, lon); - _mav_put_float(buf, 60, alt); - _mav_put_float(buf, 64, std_dev_horz); - _mav_put_float(buf, 68, std_dev_vert); - _mav_put_float(buf, 72, vn); - _mav_put_float(buf, 76, ve); - _mav_put_float(buf, 80, vd); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, buf, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif -#else - mavlink_sim_state_t *packet = (mavlink_sim_state_t *)msgbuf; - packet->q1 = q1; - packet->q2 = q2; - packet->q3 = q3; - packet->q4 = q4; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->xacc = xacc; - packet->yacc = yacc; - packet->zacc = zacc; - packet->xgyro = xgyro; - packet->ygyro = ygyro; - packet->zgyro = zgyro; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->std_dev_horz = std_dev_horz; - packet->std_dev_vert = std_dev_vert; - packet->vn = vn; - packet->ve = ve; - packet->vd = vd; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN, MAVLINK_MSG_ID_SIM_STATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIM_STATE, (const char *)packet, MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SIM_STATE UNPACKING - - -/** - * @brief Get field q1 from sim_state message - * - * @return True attitude quaternion component 1 - */ -static inline float mavlink_msg_sim_state_get_q1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field q2 from sim_state message - * - * @return True attitude quaternion component 2 - */ -static inline float mavlink_msg_sim_state_get_q2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field q3 from sim_state message - * - * @return True attitude quaternion component 3 - */ -static inline float mavlink_msg_sim_state_get_q3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field q4 from sim_state message - * - * @return True attitude quaternion component 4 - */ -static inline float mavlink_msg_sim_state_get_q4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field roll from sim_state message - * - * @return Attitude roll expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field pitch from sim_state message - * - * @return Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field yaw from sim_state message - * - * @return Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs - */ -static inline float mavlink_msg_sim_state_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field xacc from sim_state message - * - * @return X acceleration m/s/s - */ -static inline float mavlink_msg_sim_state_get_xacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field yacc from sim_state message - * - * @return Y acceleration m/s/s - */ -static inline float mavlink_msg_sim_state_get_yacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field zacc from sim_state message - * - * @return Z acceleration m/s/s - */ -static inline float mavlink_msg_sim_state_get_zacc(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field xgyro from sim_state message - * - * @return Angular speed around X axis rad/s - */ -static inline float mavlink_msg_sim_state_get_xgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field ygyro from sim_state message - * - * @return Angular speed around Y axis rad/s - */ -static inline float mavlink_msg_sim_state_get_ygyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field zgyro from sim_state message - * - * @return Angular speed around Z axis rad/s - */ -static inline float mavlink_msg_sim_state_get_zgyro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field lat from sim_state message - * - * @return Latitude in degrees - */ -static inline float mavlink_msg_sim_state_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field lon from sim_state message - * - * @return Longitude in degrees - */ -static inline float mavlink_msg_sim_state_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field alt from sim_state message - * - * @return Altitude in meters - */ -static inline float mavlink_msg_sim_state_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 60); -} - -/** - * @brief Get field std_dev_horz from sim_state message - * - * @return Horizontal position standard deviation - */ -static inline float mavlink_msg_sim_state_get_std_dev_horz(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 64); -} - -/** - * @brief Get field std_dev_vert from sim_state message - * - * @return Vertical position standard deviation - */ -static inline float mavlink_msg_sim_state_get_std_dev_vert(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 68); -} - -/** - * @brief Get field vn from sim_state message - * - * @return True velocity in m/s in NORTH direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_vn(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 72); -} - -/** - * @brief Get field ve from sim_state message - * - * @return True velocity in m/s in EAST direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_ve(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 76); -} - -/** - * @brief Get field vd from sim_state message - * - * @return True velocity in m/s in DOWN direction in earth-fixed NED frame - */ -static inline float mavlink_msg_sim_state_get_vd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 80); -} - -/** - * @brief Decode a sim_state message into a struct - * - * @param msg The message to decode - * @param sim_state C-struct to decode the message contents into - */ -static inline void mavlink_msg_sim_state_decode(const mavlink_message_t* msg, mavlink_sim_state_t* sim_state) -{ -#if MAVLINK_NEED_BYTE_SWAP - sim_state->q1 = mavlink_msg_sim_state_get_q1(msg); - sim_state->q2 = mavlink_msg_sim_state_get_q2(msg); - sim_state->q3 = mavlink_msg_sim_state_get_q3(msg); - sim_state->q4 = mavlink_msg_sim_state_get_q4(msg); - sim_state->roll = mavlink_msg_sim_state_get_roll(msg); - sim_state->pitch = mavlink_msg_sim_state_get_pitch(msg); - sim_state->yaw = mavlink_msg_sim_state_get_yaw(msg); - sim_state->xacc = mavlink_msg_sim_state_get_xacc(msg); - sim_state->yacc = mavlink_msg_sim_state_get_yacc(msg); - sim_state->zacc = mavlink_msg_sim_state_get_zacc(msg); - sim_state->xgyro = mavlink_msg_sim_state_get_xgyro(msg); - sim_state->ygyro = mavlink_msg_sim_state_get_ygyro(msg); - sim_state->zgyro = mavlink_msg_sim_state_get_zgyro(msg); - sim_state->lat = mavlink_msg_sim_state_get_lat(msg); - sim_state->lon = mavlink_msg_sim_state_get_lon(msg); - sim_state->alt = mavlink_msg_sim_state_get_alt(msg); - sim_state->std_dev_horz = mavlink_msg_sim_state_get_std_dev_horz(msg); - sim_state->std_dev_vert = mavlink_msg_sim_state_get_std_dev_vert(msg); - sim_state->vn = mavlink_msg_sim_state_get_vn(msg); - sim_state->ve = mavlink_msg_sim_state_get_ve(msg); - sim_state->vd = mavlink_msg_sim_state_get_vd(msg); -#else - memcpy(sim_state, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SIM_STATE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h deleted file mode 100644 index be2629dd8..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h +++ /dev/null @@ -1,401 +0,0 @@ -// MESSAGE STATE_CORRECTION PACKING - -#define MAVLINK_MSG_ID_STATE_CORRECTION 64 - -typedef struct __mavlink_state_correction_t -{ - float xErr; ///< x position error - float yErr; ///< y position error - float zErr; ///< z position error - float rollErr; ///< roll error (radians) - float pitchErr; ///< pitch error (radians) - float yawErr; ///< yaw error (radians) - float vxErr; ///< x velocity - float vyErr; ///< y velocity - float vzErr; ///< z velocity -} mavlink_state_correction_t; - -#define MAVLINK_MSG_ID_STATE_CORRECTION_LEN 36 -#define MAVLINK_MSG_ID_64_LEN 36 - -#define MAVLINK_MSG_ID_STATE_CORRECTION_CRC 130 -#define MAVLINK_MSG_ID_64_CRC 130 - - - -#define MAVLINK_MESSAGE_INFO_STATE_CORRECTION { \ - "STATE_CORRECTION", \ - 9, \ - { { "xErr", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_state_correction_t, xErr) }, \ - { "yErr", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_state_correction_t, yErr) }, \ - { "zErr", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_state_correction_t, zErr) }, \ - { "rollErr", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_state_correction_t, rollErr) }, \ - { "pitchErr", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_state_correction_t, pitchErr) }, \ - { "yawErr", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_state_correction_t, yawErr) }, \ - { "vxErr", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_state_correction_t, vxErr) }, \ - { "vyErr", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_state_correction_t, vyErr) }, \ - { "vzErr", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_state_correction_t, vzErr) }, \ - } \ -} - - -/** - * @brief Pack a state_correction message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param xErr x position error - * @param yErr y position error - * @param zErr z position error - * @param rollErr roll error (radians) - * @param pitchErr pitch error (radians) - * @param yawErr yaw error (radians) - * @param vxErr x velocity - * @param vyErr y velocity - * @param vzErr z velocity - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STATE_CORRECTION_LEN]; - _mav_put_float(buf, 0, xErr); - _mav_put_float(buf, 4, yErr); - _mav_put_float(buf, 8, zErr); - _mav_put_float(buf, 12, rollErr); - _mav_put_float(buf, 16, pitchErr); - _mav_put_float(buf, 20, yawErr); - _mav_put_float(buf, 24, vxErr); - _mav_put_float(buf, 28, vyErr); - _mav_put_float(buf, 32, vzErr); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#else - mavlink_state_correction_t packet; - packet.xErr = xErr; - packet.yErr = yErr; - packet.zErr = zErr; - packet.rollErr = rollErr; - packet.pitchErr = pitchErr; - packet.yawErr = yawErr; - packet.vxErr = vxErr; - packet.vyErr = vyErr; - packet.vzErr = vzErr; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#endif -} - -/** - * @brief Pack a state_correction message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param xErr x position error - * @param yErr y position error - * @param zErr z position error - * @param rollErr roll error (radians) - * @param pitchErr pitch error (radians) - * @param yawErr yaw error (radians) - * @param vxErr x velocity - * @param vyErr y velocity - * @param vzErr z velocity - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float xErr,float yErr,float zErr,float rollErr,float pitchErr,float yawErr,float vxErr,float vyErr,float vzErr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STATE_CORRECTION_LEN]; - _mav_put_float(buf, 0, xErr); - _mav_put_float(buf, 4, yErr); - _mav_put_float(buf, 8, zErr); - _mav_put_float(buf, 12, rollErr); - _mav_put_float(buf, 16, pitchErr); - _mav_put_float(buf, 20, yawErr); - _mav_put_float(buf, 24, vxErr); - _mav_put_float(buf, 28, vyErr); - _mav_put_float(buf, 32, vzErr); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#else - mavlink_state_correction_t packet; - packet.xErr = xErr; - packet.yErr = yErr; - packet.zErr = zErr; - packet.rollErr = rollErr; - packet.pitchErr = pitchErr; - packet.yawErr = yawErr; - packet.vxErr = vxErr; - packet.vyErr = vyErr; - packet.vzErr = vzErr; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#endif -} - -/** - * @brief Encode a state_correction struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param state_correction C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction) -{ - return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr); -} - -/** - * @brief Encode a state_correction struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param state_correction C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_state_correction_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction) -{ - return mavlink_msg_state_correction_pack_chan(system_id, component_id, chan, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr); -} - -/** - * @brief Send a state_correction message - * @param chan MAVLink channel to send the message - * - * @param xErr x position error - * @param yErr y position error - * @param zErr z position error - * @param rollErr roll error (radians) - * @param pitchErr pitch error (radians) - * @param yawErr yaw error (radians) - * @param vxErr x velocity - * @param vyErr y velocity - * @param vzErr z velocity - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STATE_CORRECTION_LEN]; - _mav_put_float(buf, 0, xErr); - _mav_put_float(buf, 4, yErr); - _mav_put_float(buf, 8, zErr); - _mav_put_float(buf, 12, rollErr); - _mav_put_float(buf, 16, pitchErr); - _mav_put_float(buf, 20, yawErr); - _mav_put_float(buf, 24, vxErr); - _mav_put_float(buf, 28, vyErr); - _mav_put_float(buf, 32, vzErr); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#endif -#else - mavlink_state_correction_t packet; - packet.xErr = xErr; - packet.yErr = yErr; - packet.zErr = zErr; - packet.rollErr = rollErr; - packet.pitchErr = pitchErr; - packet.yawErr = yawErr; - packet.vxErr = vxErr; - packet.vyErr = vyErr; - packet.vzErr = vzErr; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)&packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)&packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_STATE_CORRECTION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_state_correction_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, xErr); - _mav_put_float(buf, 4, yErr); - _mav_put_float(buf, 8, zErr); - _mav_put_float(buf, 12, rollErr); - _mav_put_float(buf, 16, pitchErr); - _mav_put_float(buf, 20, yawErr); - _mav_put_float(buf, 24, vxErr); - _mav_put_float(buf, 28, vyErr); - _mav_put_float(buf, 32, vzErr); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#endif -#else - mavlink_state_correction_t *packet = (mavlink_state_correction_t *)msgbuf; - packet->xErr = xErr; - packet->yErr = yErr; - packet->zErr = zErr; - packet->rollErr = rollErr; - packet->pitchErr = pitchErr; - packet->yawErr = yawErr; - packet->vxErr = vxErr; - packet->vyErr = vyErr; - packet->vzErr = vzErr; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN, MAVLINK_MSG_ID_STATE_CORRECTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)packet, MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE STATE_CORRECTION UNPACKING - - -/** - * @brief Get field xErr from state_correction message - * - * @return x position error - */ -static inline float mavlink_msg_state_correction_get_xErr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field yErr from state_correction message - * - * @return y position error - */ -static inline float mavlink_msg_state_correction_get_yErr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field zErr from state_correction message - * - * @return z position error - */ -static inline float mavlink_msg_state_correction_get_zErr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field rollErr from state_correction message - * - * @return roll error (radians) - */ -static inline float mavlink_msg_state_correction_get_rollErr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pitchErr from state_correction message - * - * @return pitch error (radians) - */ -static inline float mavlink_msg_state_correction_get_pitchErr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field yawErr from state_correction message - * - * @return yaw error (radians) - */ -static inline float mavlink_msg_state_correction_get_yawErr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field vxErr from state_correction message - * - * @return x velocity - */ -static inline float mavlink_msg_state_correction_get_vxErr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field vyErr from state_correction message - * - * @return y velocity - */ -static inline float mavlink_msg_state_correction_get_vyErr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field vzErr from state_correction message - * - * @return z velocity - */ -static inline float mavlink_msg_state_correction_get_vzErr(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Decode a state_correction message into a struct - * - * @param msg The message to decode - * @param state_correction C-struct to decode the message contents into - */ -static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction) -{ -#if MAVLINK_NEED_BYTE_SWAP - state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg); - state_correction->yErr = mavlink_msg_state_correction_get_yErr(msg); - state_correction->zErr = mavlink_msg_state_correction_get_zErr(msg); - state_correction->rollErr = mavlink_msg_state_correction_get_rollErr(msg); - state_correction->pitchErr = mavlink_msg_state_correction_get_pitchErr(msg); - state_correction->yawErr = mavlink_msg_state_correction_get_yawErr(msg); - state_correction->vxErr = mavlink_msg_state_correction_get_vxErr(msg); - state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg); - state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg); -#else - memcpy(state_correction, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_STATE_CORRECTION_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h deleted file mode 100644 index c8c2547b3..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_statustext.h +++ /dev/null @@ -1,225 +0,0 @@ -// MESSAGE STATUSTEXT PACKING - -#define MAVLINK_MSG_ID_STATUSTEXT 253 - -typedef struct __mavlink_statustext_t -{ - uint8_t severity; ///< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - char text[50]; ///< Status text message, without null termination character -} mavlink_statustext_t; - -#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51 -#define MAVLINK_MSG_ID_253_LEN 51 - -#define MAVLINK_MSG_ID_STATUSTEXT_CRC 83 -#define MAVLINK_MSG_ID_253_CRC 83 - -#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50 - -#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \ - "STATUSTEXT", \ - 2, \ - { { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \ - { "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \ - } \ -} - - -/** - * @brief Pack a statustext message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t severity, const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; - _mav_put_uint8_t(buf, 0, severity); - _mav_put_char_array(buf, 1, text, 50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#else - mavlink_statustext_t packet; - packet.severity = severity; - mav_array_memcpy(packet.text, text, sizeof(char)*50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif -} - -/** - * @brief Pack a statustext message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t severity,const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; - _mav_put_uint8_t(buf, 0, severity); - _mav_put_char_array(buf, 1, text, 50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#else - mavlink_statustext_t packet; - packet.severity = severity; - mav_array_memcpy(packet.text, text, sizeof(char)*50); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_STATUSTEXT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif -} - -/** - * @brief Encode a statustext struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param statustext C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext) -{ - return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text); -} - -/** - * @brief Encode a statustext struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param statustext C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_statustext_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_statustext_t* statustext) -{ - return mavlink_msg_statustext_pack_chan(system_id, component_id, chan, msg, statustext->severity, statustext->text); -} - -/** - * @brief Send a statustext message - * @param chan MAVLink channel to send the message - * - * @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - * @param text Status text message, without null termination character - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_STATUSTEXT_LEN]; - _mav_put_uint8_t(buf, 0, severity); - _mav_put_char_array(buf, 1, text, 50); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif -#else - mavlink_statustext_t packet; - packet.severity = severity; - mav_array_memcpy(packet.text, text, sizeof(char)*50); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_STATUSTEXT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_statustext_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t severity, const char *text) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, severity); - _mav_put_char_array(buf, 1, text, 50); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif -#else - mavlink_statustext_t *packet = (mavlink_statustext_t *)msgbuf; - packet->severity = severity; - mav_array_memcpy(packet->text, text, sizeof(char)*50); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)packet, MAVLINK_MSG_ID_STATUSTEXT_LEN, MAVLINK_MSG_ID_STATUSTEXT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)packet, MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE STATUSTEXT UNPACKING - - -/** - * @brief Get field severity from statustext message - * - * @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY. - */ -static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field text from statustext message - * - * @return Status text message, without null termination character - */ -static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text) -{ - return _MAV_RETURN_char_array(msg, text, 50, 1); -} - -/** - * @brief Decode a statustext message into a struct - * - * @param msg The message to decode - * @param statustext C-struct to decode the message contents into - */ -static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext) -{ -#if MAVLINK_NEED_BYTE_SWAP - statustext->severity = mavlink_msg_statustext_get_severity(msg); - mavlink_msg_statustext_get_text(msg, statustext->text); -#else - memcpy(statustext, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_STATUSTEXT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h deleted file mode 100644 index 1b1730d5f..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h +++ /dev/null @@ -1,497 +0,0 @@ -// MESSAGE SYS_STATUS PACKING - -#define MAVLINK_MSG_ID_SYS_STATUS 1 - -typedef struct __mavlink_sys_status_t -{ - uint32_t onboard_control_sensors_present; ///< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - uint32_t onboard_control_sensors_enabled; ///< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - uint32_t onboard_control_sensors_health; ///< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - uint16_t voltage_battery; ///< Battery voltage, in millivolts (1 = 1 millivolt) - int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - uint16_t drop_rate_comm; ///< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - uint16_t errors_comm; ///< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - uint16_t errors_count1; ///< Autopilot-specific errors - uint16_t errors_count2; ///< Autopilot-specific errors - uint16_t errors_count3; ///< Autopilot-specific errors - uint16_t errors_count4; ///< Autopilot-specific errors - int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery -} mavlink_sys_status_t; - -#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31 -#define MAVLINK_MSG_ID_1_LEN 31 - -#define MAVLINK_MSG_ID_SYS_STATUS_CRC 124 -#define MAVLINK_MSG_ID_1_CRC 124 - - - -#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \ - "SYS_STATUS", \ - 13, \ - { { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \ - { "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \ - { "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \ - { "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \ - { "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \ - { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \ - { "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \ - { "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \ - { "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \ - { "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \ - { "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \ - { "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \ - { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \ - } \ -} - - -/** - * @brief Pack a sys_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); - _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); - _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#else - mavlink_sys_status_t packet; - packet.onboard_control_sensors_present = onboard_control_sensors_present; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif -} - -/** - * @brief Pack a sys_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t onboard_control_sensors_present,uint32_t onboard_control_sensors_enabled,uint32_t onboard_control_sensors_health,uint16_t load,uint16_t voltage_battery,int16_t current_battery,int8_t battery_remaining,uint16_t drop_rate_comm,uint16_t errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); - _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); - _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#else - mavlink_sys_status_t packet; - packet.onboard_control_sensors_present = onboard_control_sensors_present; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYS_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif -} - -/** - * @brief Encode a sys_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param sys_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) -{ - return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); -} - -/** - * @brief Encode a sys_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sys_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status) -{ - return mavlink_msg_sys_status_pack_chan(system_id, component_id, chan, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4); -} - -/** - * @brief Send a sys_status message - * @param chan MAVLink channel to send the message - * - * @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - * @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - * @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt) - * @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - * @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - * @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - * @param errors_count1 Autopilot-specific errors - * @param errors_count2 Autopilot-specific errors - * @param errors_count3 Autopilot-specific errors - * @param errors_count4 Autopilot-specific errors - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYS_STATUS_LEN]; - _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); - _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); - _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif -#else - mavlink_sys_status_t packet; - packet.onboard_control_sensors_present = onboard_control_sensors_present; - packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet.onboard_control_sensors_health = onboard_control_sensors_health; - packet.load = load; - packet.voltage_battery = voltage_battery; - packet.current_battery = current_battery; - packet.drop_rate_comm = drop_rate_comm; - packet.errors_comm = errors_comm; - packet.errors_count1 = errors_count1; - packet.errors_count2 = errors_count2; - packet.errors_count3 = errors_count3; - packet.errors_count4 = errors_count4; - packet.battery_remaining = battery_remaining; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SYS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sys_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, onboard_control_sensors_present); - _mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled); - _mav_put_uint32_t(buf, 8, onboard_control_sensors_health); - _mav_put_uint16_t(buf, 12, load); - _mav_put_uint16_t(buf, 14, voltage_battery); - _mav_put_int16_t(buf, 16, current_battery); - _mav_put_uint16_t(buf, 18, drop_rate_comm); - _mav_put_uint16_t(buf, 20, errors_comm); - _mav_put_uint16_t(buf, 22, errors_count1); - _mav_put_uint16_t(buf, 24, errors_count2); - _mav_put_uint16_t(buf, 26, errors_count3); - _mav_put_uint16_t(buf, 28, errors_count4); - _mav_put_int8_t(buf, 30, battery_remaining); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif -#else - mavlink_sys_status_t *packet = (mavlink_sys_status_t *)msgbuf; - packet->onboard_control_sensors_present = onboard_control_sensors_present; - packet->onboard_control_sensors_enabled = onboard_control_sensors_enabled; - packet->onboard_control_sensors_health = onboard_control_sensors_health; - packet->load = load; - packet->voltage_battery = voltage_battery; - packet->current_battery = current_battery; - packet->drop_rate_comm = drop_rate_comm; - packet->errors_comm = errors_comm; - packet->errors_count1 = errors_count1; - packet->errors_count2 = errors_count2; - packet->errors_count3 = errors_count3; - packet->errors_count4 = errors_count4; - packet->battery_remaining = battery_remaining; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_LEN, MAVLINK_MSG_ID_SYS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)packet, MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SYS_STATUS UNPACKING - - -/** - * @brief Get field onboard_control_sensors_present from sys_status message - * - * @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field onboard_control_sensors_enabled from sys_status message - * - * @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field onboard_control_sensors_health from sys_status message - * - * @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices defined by ENUM MAV_SYS_STATUS_SENSOR - */ -static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field load from sys_status message - * - * @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 - */ -static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field voltage_battery from sys_status message - * - * @return Battery voltage, in millivolts (1 = 1 millivolt) - */ -static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 14); -} - -/** - * @brief Get field current_battery from sys_status message - * - * @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current - */ -static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field battery_remaining from sys_status message - * - * @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery - */ -static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 30); -} - -/** - * @brief Get field drop_rate_comm from sys_status message - * - * @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - */ -static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field errors_comm from sys_status message - * - * @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 20); -} - -/** - * @brief Get field errors_count1 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 22); -} - -/** - * @brief Get field errors_count2 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field errors_count3 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 26); -} - -/** - * @brief Get field errors_count4 from sys_status message - * - * @return Autopilot-specific errors - */ -static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 28); -} - -/** - * @brief Decode a sys_status message into a struct - * - * @param msg The message to decode - * @param sys_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg); - sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg); - sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg); - sys_status->load = mavlink_msg_sys_status_get_load(msg); - sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg); - sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg); - sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg); - sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg); - sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg); - sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg); - sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg); - sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg); - sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg); -#else - memcpy(sys_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYS_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h deleted file mode 100644 index 988c669c3..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_system_time.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE SYSTEM_TIME PACKING - -#define MAVLINK_MSG_ID_SYSTEM_TIME 2 - -typedef struct __mavlink_system_time_t -{ - uint64_t time_unix_usec; ///< Timestamp of the master clock in microseconds since UNIX epoch. - uint32_t time_boot_ms; ///< Timestamp of the component clock since boot time in milliseconds. -} mavlink_system_time_t; - -#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12 -#define MAVLINK_MSG_ID_2_LEN 12 - -#define MAVLINK_MSG_ID_SYSTEM_TIME_CRC 137 -#define MAVLINK_MSG_ID_2_CRC 137 - - - -#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \ - "SYSTEM_TIME", \ - 2, \ - { { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \ - { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \ - } \ -} - - -/** - * @brief Pack a system_time message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; - _mav_put_uint64_t(buf, 0, time_unix_usec); - _mav_put_uint32_t(buf, 8, time_boot_ms); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#else - mavlink_system_time_t packet; - packet.time_unix_usec = time_unix_usec; - packet.time_boot_ms = time_boot_ms; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif -} - -/** - * @brief Pack a system_time message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t time_unix_usec,uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; - _mav_put_uint64_t(buf, 0, time_unix_usec); - _mav_put_uint32_t(buf, 8, time_boot_ms); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#else - mavlink_system_time_t packet; - packet.time_unix_usec = time_unix_usec; - packet.time_boot_ms = time_boot_ms; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif -} - -/** - * @brief Encode a system_time struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param system_time C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time) -{ - return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms); -} - -/** - * @brief Encode a system_time struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param system_time C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_system_time_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_system_time_t* system_time) -{ - return mavlink_msg_system_time_pack_chan(system_id, component_id, chan, msg, system_time->time_unix_usec, system_time->time_boot_ms); -} - -/** - * @brief Send a system_time message - * @param chan MAVLink channel to send the message - * - * @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch. - * @param time_boot_ms Timestamp of the component clock since boot time in milliseconds. - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYSTEM_TIME_LEN]; - _mav_put_uint64_t(buf, 0, time_unix_usec); - _mav_put_uint32_t(buf, 8, time_boot_ms); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif -#else - mavlink_system_time_t packet; - packet.time_unix_usec = time_unix_usec; - packet.time_boot_ms = time_boot_ms; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SYSTEM_TIME_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_system_time_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, time_unix_usec); - _mav_put_uint32_t(buf, 8, time_boot_ms); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif -#else - mavlink_system_time_t *packet = (mavlink_system_time_t *)msgbuf; - packet->time_unix_usec = time_unix_usec; - packet->time_boot_ms = time_boot_ms; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN, MAVLINK_MSG_ID_SYSTEM_TIME_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)packet, MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SYSTEM_TIME UNPACKING - - -/** - * @brief Get field time_unix_usec from system_time message - * - * @return Timestamp of the master clock in microseconds since UNIX epoch. - */ -static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field time_boot_ms from system_time message - * - * @return Timestamp of the component clock since boot time in milliseconds. - */ -static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Decode a system_time message into a struct - * - * @param msg The message to decode - * @param system_time C-struct to decode the message contents into - */ -static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time) -{ -#if MAVLINK_NEED_BYTE_SWAP - system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg); - system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg); -#else - memcpy(system_time, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYSTEM_TIME_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h deleted file mode 100644 index b130ee50b..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE VFR_HUD PACKING - -#define MAVLINK_MSG_ID_VFR_HUD 74 - -typedef struct __mavlink_vfr_hud_t -{ - float airspeed; ///< Current airspeed in m/s - float groundspeed; ///< Current ground speed in m/s - float alt; ///< Current altitude (MSL), in meters - float climb; ///< Current climb rate in meters/second - int16_t heading; ///< Current heading in degrees, in compass units (0..360, 0=north) - uint16_t throttle; ///< Current throttle setting in integer percent, 0 to 100 -} mavlink_vfr_hud_t; - -#define MAVLINK_MSG_ID_VFR_HUD_LEN 20 -#define MAVLINK_MSG_ID_74_LEN 20 - -#define MAVLINK_MSG_ID_VFR_HUD_CRC 20 -#define MAVLINK_MSG_ID_74_CRC 20 - - - -#define MAVLINK_MESSAGE_INFO_VFR_HUD { \ - "VFR_HUD", \ - 6, \ - { { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \ - { "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \ - { "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \ - { "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \ - { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \ - } \ -} - - -/** - * @brief Pack a vfr_hud message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VFR_HUD; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif -} - -/** - * @brief Pack a vfr_hud message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VFR_HUD; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif -} - -/** - * @brief Encode a vfr_hud struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vfr_hud C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) -{ - return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -} - -/** - * @brief Encode a vfr_hud struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vfr_hud C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vfr_hud_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud) -{ - return mavlink_msg_vfr_hud_pack_chan(system_id, component_id, chan, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb); -} - -/** - * @brief Send a vfr_hud message - * @param chan MAVLink channel to send the message - * - * @param airspeed Current airspeed in m/s - * @param groundspeed Current ground speed in m/s - * @param heading Current heading in degrees, in compass units (0..360, 0=north) - * @param throttle Current throttle setting in integer percent, 0 to 100 - * @param alt Current altitude (MSL), in meters - * @param climb Current climb rate in meters/second - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VFR_HUD_LEN]; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif -#else - mavlink_vfr_hud_t packet; - packet.airspeed = airspeed; - packet.groundspeed = groundspeed; - packet.alt = alt; - packet.climb = climb; - packet.heading = heading; - packet.throttle = throttle; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_VFR_HUD_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vfr_hud_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, airspeed); - _mav_put_float(buf, 4, groundspeed); - _mav_put_float(buf, 8, alt); - _mav_put_float(buf, 12, climb); - _mav_put_int16_t(buf, 16, heading); - _mav_put_uint16_t(buf, 18, throttle); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif -#else - mavlink_vfr_hud_t *packet = (mavlink_vfr_hud_t *)msgbuf; - packet->airspeed = airspeed; - packet->groundspeed = groundspeed; - packet->alt = alt; - packet->climb = climb; - packet->heading = heading; - packet->throttle = throttle; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN, MAVLINK_MSG_ID_VFR_HUD_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)packet, MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE VFR_HUD UNPACKING - - -/** - * @brief Get field airspeed from vfr_hud message - * - * @return Current airspeed in m/s - */ -static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field groundspeed from vfr_hud message - * - * @return Current ground speed in m/s - */ -static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field heading from vfr_hud message - * - * @return Current heading in degrees, in compass units (0..360, 0=north) - */ -static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field throttle from vfr_hud message - * - * @return Current throttle setting in integer percent, 0 to 100 - */ -static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field alt from vfr_hud message - * - * @return Current altitude (MSL), in meters - */ -static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field climb from vfr_hud message - * - * @return Current climb rate in meters/second - */ -static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a vfr_hud message into a struct - * - * @param msg The message to decode - * @param vfr_hud C-struct to decode the message contents into - */ -static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud) -{ -#if MAVLINK_NEED_BYTE_SWAP - vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg); - vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg); - vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg); - vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg); - vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg); - vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg); -#else - memcpy(vfr_hud, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VFR_HUD_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h deleted file mode 100644 index b3fa7bc1c..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE VICON_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104 - -typedef struct __mavlink_vicon_position_estimate_t -{ - uint64_t usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot) - float x; ///< Global X position - float y; ///< Global Y position - float z; ///< Global Z position - float roll; ///< Roll angle in rad - float pitch; ///< Pitch angle in rad - float yaw; ///< Yaw angle in rad -} mavlink_vicon_position_estimate_t; - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_104_LEN 32 - -#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC 56 -#define MAVLINK_MSG_ID_104_CRC 56 - - - -#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \ - "VICON_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \ - } \ -} - - -/** - * @brief Pack a vicon_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif -} - -/** - * @brief Pack a vicon_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif -} - -/** - * @brief Encode a vicon_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vicon_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ - return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); -} - -/** - * @brief Encode a vicon_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vicon_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vicon_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ - return mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, chan, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw); -} - -/** - * @brief Send a vicon_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif -#else - mavlink_vicon_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vicon_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif -#else - mavlink_vicon_position_estimate_t *packet = (mavlink_vicon_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE VICON_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vicon_position_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vicon_position_estimate message - * - * @return Global X position - */ -static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vicon_position_estimate message - * - * @return Global Y position - */ -static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vicon_position_estimate message - * - * @return Global Z position - */ -static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from vicon_position_estimate message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from vicon_position_estimate message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from vicon_position_estimate message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a vicon_position_estimate message into a struct - * - * @param msg The message to decode - * @param vicon_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP - vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg); - vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg); - vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg); - vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg); - vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg); - vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg); - vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg); -#else - memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h deleted file mode 100644 index 8f82fb682..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE VISION_POSITION_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102 - -typedef struct __mavlink_vision_position_estimate_t -{ - uint64_t usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot) - float x; ///< Global X position - float y; ///< Global Y position - float z; ///< Global Z position - float roll; ///< Roll angle in rad - float pitch; ///< Pitch angle in rad - float yaw; ///< Yaw angle in rad -} mavlink_vision_position_estimate_t; - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32 -#define MAVLINK_MSG_ID_102_LEN 32 - -#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC 158 -#define MAVLINK_MSG_ID_102_CRC 158 - - - -#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \ - "VISION_POSITION_ESTIMATE", \ - 7, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \ - } \ -} - - -/** - * @brief Pack a vision_position_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif -} - -/** - * @brief Pack a vision_position_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif -} - -/** - * @brief Encode a vision_position_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ - return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); -} - -/** - * @brief Encode a vision_position_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vision_position_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_position_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate) -{ - return mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, chan, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw); -} - -/** - * @brief Send a vision_position_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X position - * @param y Global Y position - * @param z Global Z position - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif -#else - mavlink_vision_position_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - _mav_put_float(buf, 20, roll); - _mav_put_float(buf, 24, pitch); - _mav_put_float(buf, 28, yaw); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif -#else - mavlink_vision_position_estimate_t *packet = (mavlink_vision_position_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE VISION_POSITION_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vision_position_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vision_position_estimate message - * - * @return Global X position - */ -static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vision_position_estimate message - * - * @return Global Y position - */ -static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vision_position_estimate message - * - * @return Global Z position - */ -static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field roll from vision_position_estimate message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field pitch from vision_position_estimate message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field yaw from vision_position_estimate message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Decode a vision_position_estimate message into a struct - * - * @param msg The message to decode - * @param vision_position_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP - vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg); - vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg); - vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg); - vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg); - vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg); - vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg); - vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg); -#else - memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h deleted file mode 100644 index 7528014c7..000000000 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE VISION_SPEED_ESTIMATE PACKING - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103 - -typedef struct __mavlink_vision_speed_estimate_t -{ - uint64_t usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot) - float x; ///< Global X speed - float y; ///< Global Y speed - float z; ///< Global Z speed -} mavlink_vision_speed_estimate_t; - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20 -#define MAVLINK_MSG_ID_103_LEN 20 - -#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC 208 -#define MAVLINK_MSG_ID_103_CRC 208 - - - -#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \ - "VISION_SPEED_ESTIMATE", \ - 4, \ - { { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \ - { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \ - } \ -} - - -/** - * @brief Pack a vision_speed_estimate message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif -} - -/** - * @brief Pack a vision_speed_estimate message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t usec,float x,float y,float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif -} - -/** - * @brief Encode a vision_speed_estimate struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param vision_speed_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ - return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); -} - -/** - * @brief Encode a vision_speed_estimate struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vision_speed_estimate C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_vision_speed_estimate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ - return mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, chan, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z); -} - -/** - * @brief Send a vision_speed_estimate message - * @param chan MAVLink channel to send the message - * - * @param usec Timestamp (microseconds, synced to UNIX time or since system boot) - * @param x Global X speed - * @param y Global Y speed - * @param z Global Z speed - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN]; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif -#else - mavlink_vision_speed_estimate_t packet; - packet.usec = usec; - packet.x = x; - packet.y = y; - packet.z = z; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_vision_speed_estimate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t usec, float x, float y, float z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, usec); - _mav_put_float(buf, 8, x); - _mav_put_float(buf, 12, y); - _mav_put_float(buf, 16, z); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif -#else - mavlink_vision_speed_estimate_t *packet = (mavlink_vision_speed_estimate_t *)msgbuf; - packet->usec = usec; - packet->x = x; - packet->y = y; - packet->z = z; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE VISION_SPEED_ESTIMATE UNPACKING - - -/** - * @brief Get field usec from vision_speed_estimate message - * - * @return Timestamp (microseconds, synced to UNIX time or since system boot) - */ -static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field x from vision_speed_estimate message - * - * @return Global X speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field y from vision_speed_estimate message - * - * @return Global Y speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field z from vision_speed_estimate message - * - * @return Global Z speed - */ -static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a vision_speed_estimate message into a struct - * - * @param msg The message to decode - * @param vision_speed_estimate C-struct to decode the message contents into - */ -static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate) -{ -#if MAVLINK_NEED_BYTE_SWAP - vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg); - vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg); - vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg); - vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg); -#else - memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/common/testsuite.h b/mavlink/include/mavlink/v1.0/common/testsuite.h deleted file mode 100644 index de23fcb2a..000000000 --- a/mavlink/include/mavlink/v1.0/common/testsuite.h +++ /dev/null @@ -1,5872 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from common.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef COMMON_TESTSUITE_H -#define COMMON_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL - -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - - mavlink_test_common(system_id, component_id, last_msg); -} -#endif - - - - -static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_heartbeat_t packet_in = { - 963497464, - }17, - }84, - }151, - }218, - }3, - }; - mavlink_heartbeat_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.custom_mode = packet_in.custom_mode; - packet1.type = packet_in.type; - packet1.autopilot = packet_in.autopilot; - packet1.base_mode = packet_in.base_mode; - packet1.system_status = packet_in.system_status; - packet1.mavlink_version = packet_in.mavlink_version; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status ); - mavlink_msg_heartbeat_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; i 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* 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. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - 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_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 sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ - MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ - MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ - MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */ - 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| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - 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| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ - MAV_CMD_ENUM_END=501, /* | */ -}; -#endif - -#include "../common/common.h" - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_flexifunction_set.h" -#include "./mavlink_msg_flexifunction_read_req.h" -#include "./mavlink_msg_flexifunction_buffer_function.h" -#include "./mavlink_msg_flexifunction_buffer_function_ack.h" -#include "./mavlink_msg_flexifunction_directory.h" -#include "./mavlink_msg_flexifunction_directory_ack.h" -#include "./mavlink_msg_flexifunction_command.h" -#include "./mavlink_msg_flexifunction_command_ack.h" -#include "./mavlink_msg_serial_udb_extra_f2_a.h" -#include "./mavlink_msg_serial_udb_extra_f2_b.h" -#include "./mavlink_msg_serial_udb_extra_f4.h" -#include "./mavlink_msg_serial_udb_extra_f5.h" -#include "./mavlink_msg_serial_udb_extra_f6.h" -#include "./mavlink_msg_serial_udb_extra_f7.h" -#include "./mavlink_msg_serial_udb_extra_f8.h" -#include "./mavlink_msg_serial_udb_extra_f13.h" -#include "./mavlink_msg_serial_udb_extra_f14.h" -#include "./mavlink_msg_serial_udb_extra_f15.h" -#include "./mavlink_msg_serial_udb_extra_f16.h" -#include "./mavlink_msg_altitudes.h" -#include "./mavlink_msg_airspeeds.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // MATRIXPILOT_H diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink.h deleted file mode 100644 index 7e62a9719..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink.h +++ /dev/null @@ -1,27 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from matrixpilot.xml - * @see http://pixhawk.ethz.ch/software/mavlink - */ -#ifndef MAVLINK_H -#define MAVLINK_H - -#ifndef MAVLINK_STX -#define MAVLINK_STX 254 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#include "version.h" -#include "matrixpilot.h" - -#endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h deleted file mode 100644 index c834a3df0..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_airspeeds.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE AIRSPEEDS PACKING - -#define MAVLINK_MSG_ID_AIRSPEEDS 182 - -typedef struct __mavlink_airspeeds_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - int16_t airspeed_imu; ///< Airspeed estimate from IMU, cm/s - int16_t airspeed_pitot; ///< Pitot measured forward airpseed, cm/s - int16_t airspeed_hot_wire; ///< Hot wire anenometer measured airspeed, cm/s - int16_t airspeed_ultrasonic; ///< Ultrasonic measured airspeed, cm/s - int16_t aoa; ///< Angle of attack sensor, degrees * 10 - int16_t aoy; ///< Yaw angle sensor, degrees * 10 -} mavlink_airspeeds_t; - -#define MAVLINK_MSG_ID_AIRSPEEDS_LEN 16 -#define MAVLINK_MSG_ID_182_LEN 16 - -#define MAVLINK_MSG_ID_AIRSPEEDS_CRC 154 -#define MAVLINK_MSG_ID_182_CRC 154 - - - -#define MAVLINK_MESSAGE_INFO_AIRSPEEDS { \ - "AIRSPEEDS", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_airspeeds_t, time_boot_ms) }, \ - { "airspeed_imu", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_airspeeds_t, airspeed_imu) }, \ - { "airspeed_pitot", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_airspeeds_t, airspeed_pitot) }, \ - { "airspeed_hot_wire", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_airspeeds_t, airspeed_hot_wire) }, \ - { "airspeed_ultrasonic", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_airspeeds_t, airspeed_ultrasonic) }, \ - { "aoa", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_airspeeds_t, aoa) }, \ - { "aoy", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_airspeeds_t, aoy) }, \ - } \ -} - - -/** - * @brief Pack a airspeeds message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param airspeed_imu Airspeed estimate from IMU, cm/s - * @param airspeed_pitot Pitot measured forward airpseed, cm/s - * @param airspeed_hot_wire Hot wire anenometer measured airspeed, cm/s - * @param airspeed_ultrasonic Ultrasonic measured airspeed, cm/s - * @param aoa Angle of attack sensor, degrees * 10 - * @param aoy Yaw angle sensor, degrees * 10 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_airspeeds_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int16_t airspeed_imu, int16_t airspeed_pitot, int16_t airspeed_hot_wire, int16_t airspeed_ultrasonic, int16_t aoa, int16_t aoy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AIRSPEEDS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, airspeed_imu); - _mav_put_int16_t(buf, 6, airspeed_pitot); - _mav_put_int16_t(buf, 8, airspeed_hot_wire); - _mav_put_int16_t(buf, 10, airspeed_ultrasonic); - _mav_put_int16_t(buf, 12, aoa); - _mav_put_int16_t(buf, 14, aoy); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#else - mavlink_airspeeds_t packet; - packet.time_boot_ms = time_boot_ms; - packet.airspeed_imu = airspeed_imu; - packet.airspeed_pitot = airspeed_pitot; - packet.airspeed_hot_wire = airspeed_hot_wire; - packet.airspeed_ultrasonic = airspeed_ultrasonic; - packet.aoa = aoa; - packet.aoy = aoy; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AIRSPEEDS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#endif -} - -/** - * @brief Pack a airspeeds message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param airspeed_imu Airspeed estimate from IMU, cm/s - * @param airspeed_pitot Pitot measured forward airpseed, cm/s - * @param airspeed_hot_wire Hot wire anenometer measured airspeed, cm/s - * @param airspeed_ultrasonic Ultrasonic measured airspeed, cm/s - * @param aoa Angle of attack sensor, degrees * 10 - * @param aoy Yaw angle sensor, degrees * 10 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_airspeeds_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int16_t airspeed_imu,int16_t airspeed_pitot,int16_t airspeed_hot_wire,int16_t airspeed_ultrasonic,int16_t aoa,int16_t aoy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AIRSPEEDS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, airspeed_imu); - _mav_put_int16_t(buf, 6, airspeed_pitot); - _mav_put_int16_t(buf, 8, airspeed_hot_wire); - _mav_put_int16_t(buf, 10, airspeed_ultrasonic); - _mav_put_int16_t(buf, 12, aoa); - _mav_put_int16_t(buf, 14, aoy); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#else - mavlink_airspeeds_t packet; - packet.time_boot_ms = time_boot_ms; - packet.airspeed_imu = airspeed_imu; - packet.airspeed_pitot = airspeed_pitot; - packet.airspeed_hot_wire = airspeed_hot_wire; - packet.airspeed_ultrasonic = airspeed_ultrasonic; - packet.aoa = aoa; - packet.aoy = aoy; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_AIRSPEEDS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#endif -} - -/** - * @brief Encode a airspeeds struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param airspeeds C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_airspeeds_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeeds_t* airspeeds) -{ - return mavlink_msg_airspeeds_pack(system_id, component_id, msg, airspeeds->time_boot_ms, airspeeds->airspeed_imu, airspeeds->airspeed_pitot, airspeeds->airspeed_hot_wire, airspeeds->airspeed_ultrasonic, airspeeds->aoa, airspeeds->aoy); -} - -/** - * @brief Encode a airspeeds struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param airspeeds C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_airspeeds_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airspeeds_t* airspeeds) -{ - return mavlink_msg_airspeeds_pack_chan(system_id, component_id, chan, msg, airspeeds->time_boot_ms, airspeeds->airspeed_imu, airspeeds->airspeed_pitot, airspeeds->airspeed_hot_wire, airspeeds->airspeed_ultrasonic, airspeeds->aoa, airspeeds->aoy); -} - -/** - * @brief Send a airspeeds message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param airspeed_imu Airspeed estimate from IMU, cm/s - * @param airspeed_pitot Pitot measured forward airpseed, cm/s - * @param airspeed_hot_wire Hot wire anenometer measured airspeed, cm/s - * @param airspeed_ultrasonic Ultrasonic measured airspeed, cm/s - * @param aoa Angle of attack sensor, degrees * 10 - * @param aoy Yaw angle sensor, degrees * 10 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_airspeeds_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t airspeed_imu, int16_t airspeed_pitot, int16_t airspeed_hot_wire, int16_t airspeed_ultrasonic, int16_t aoa, int16_t aoy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_AIRSPEEDS_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, airspeed_imu); - _mav_put_int16_t(buf, 6, airspeed_pitot); - _mav_put_int16_t(buf, 8, airspeed_hot_wire); - _mav_put_int16_t(buf, 10, airspeed_ultrasonic); - _mav_put_int16_t(buf, 12, aoa); - _mav_put_int16_t(buf, 14, aoy); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#endif -#else - mavlink_airspeeds_t packet; - packet.time_boot_ms = time_boot_ms; - packet.airspeed_imu = airspeed_imu; - packet.airspeed_pitot = airspeed_pitot; - packet.airspeed_hot_wire = airspeed_hot_wire; - packet.airspeed_ultrasonic = airspeed_ultrasonic; - packet.aoa = aoa; - packet.aoy = aoy; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_AIRSPEEDS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_airspeeds_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int16_t airspeed_imu, int16_t airspeed_pitot, int16_t airspeed_hot_wire, int16_t airspeed_ultrasonic, int16_t aoa, int16_t aoy) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int16_t(buf, 4, airspeed_imu); - _mav_put_int16_t(buf, 6, airspeed_pitot); - _mav_put_int16_t(buf, 8, airspeed_hot_wire); - _mav_put_int16_t(buf, 10, airspeed_ultrasonic); - _mav_put_int16_t(buf, 12, aoa); - _mav_put_int16_t(buf, 14, aoy); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, buf, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#endif -#else - mavlink_airspeeds_t *packet = (mavlink_airspeeds_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->airspeed_imu = airspeed_imu; - packet->airspeed_pitot = airspeed_pitot; - packet->airspeed_hot_wire = airspeed_hot_wire; - packet->airspeed_ultrasonic = airspeed_ultrasonic; - packet->aoa = aoa; - packet->aoy = aoy; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN, MAVLINK_MSG_ID_AIRSPEEDS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEEDS, (const char *)packet, MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE AIRSPEEDS UNPACKING - - -/** - * @brief Get field time_boot_ms from airspeeds message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_airspeeds_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field airspeed_imu from airspeeds message - * - * @return Airspeed estimate from IMU, cm/s - */ -static inline int16_t mavlink_msg_airspeeds_get_airspeed_imu(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field airspeed_pitot from airspeeds message - * - * @return Pitot measured forward airpseed, cm/s - */ -static inline int16_t mavlink_msg_airspeeds_get_airspeed_pitot(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field airspeed_hot_wire from airspeeds message - * - * @return Hot wire anenometer measured airspeed, cm/s - */ -static inline int16_t mavlink_msg_airspeeds_get_airspeed_hot_wire(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field airspeed_ultrasonic from airspeeds message - * - * @return Ultrasonic measured airspeed, cm/s - */ -static inline int16_t mavlink_msg_airspeeds_get_airspeed_ultrasonic(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field aoa from airspeeds message - * - * @return Angle of attack sensor, degrees * 10 - */ -static inline int16_t mavlink_msg_airspeeds_get_aoa(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field aoy from airspeeds message - * - * @return Yaw angle sensor, degrees * 10 - */ -static inline int16_t mavlink_msg_airspeeds_get_aoy(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Decode a airspeeds message into a struct - * - * @param msg The message to decode - * @param airspeeds C-struct to decode the message contents into - */ -static inline void mavlink_msg_airspeeds_decode(const mavlink_message_t* msg, mavlink_airspeeds_t* airspeeds) -{ -#if MAVLINK_NEED_BYTE_SWAP - airspeeds->time_boot_ms = mavlink_msg_airspeeds_get_time_boot_ms(msg); - airspeeds->airspeed_imu = mavlink_msg_airspeeds_get_airspeed_imu(msg); - airspeeds->airspeed_pitot = mavlink_msg_airspeeds_get_airspeed_pitot(msg); - airspeeds->airspeed_hot_wire = mavlink_msg_airspeeds_get_airspeed_hot_wire(msg); - airspeeds->airspeed_ultrasonic = mavlink_msg_airspeeds_get_airspeed_ultrasonic(msg); - airspeeds->aoa = mavlink_msg_airspeeds_get_aoa(msg); - airspeeds->aoy = mavlink_msg_airspeeds_get_aoy(msg); -#else - memcpy(airspeeds, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AIRSPEEDS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h deleted file mode 100644 index b009068ff..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_altitudes.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE ALTITUDES PACKING - -#define MAVLINK_MSG_ID_ALTITUDES 181 - -typedef struct __mavlink_altitudes_t -{ - uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot) - int32_t alt_gps; ///< GPS altitude in meters, expressed as * 1000 (millimeters), above MSL - int32_t alt_imu; ///< IMU altitude above ground in meters, expressed as * 1000 (millimeters) - int32_t alt_barometric; ///< barometeric altitude above ground in meters, expressed as * 1000 (millimeters) - int32_t alt_optical_flow; ///< Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) - int32_t alt_range_finder; ///< Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) - int32_t alt_extra; ///< Extra altitude above ground in meters, expressed as * 1000 (millimeters) -} mavlink_altitudes_t; - -#define MAVLINK_MSG_ID_ALTITUDES_LEN 28 -#define MAVLINK_MSG_ID_181_LEN 28 - -#define MAVLINK_MSG_ID_ALTITUDES_CRC 55 -#define MAVLINK_MSG_ID_181_CRC 55 - - - -#define MAVLINK_MESSAGE_INFO_ALTITUDES { \ - "ALTITUDES", \ - 7, \ - { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_altitudes_t, time_boot_ms) }, \ - { "alt_gps", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_altitudes_t, alt_gps) }, \ - { "alt_imu", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_altitudes_t, alt_imu) }, \ - { "alt_barometric", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_altitudes_t, alt_barometric) }, \ - { "alt_optical_flow", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_altitudes_t, alt_optical_flow) }, \ - { "alt_range_finder", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_altitudes_t, alt_range_finder) }, \ - { "alt_extra", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_altitudes_t, alt_extra) }, \ - } \ -} - - -/** - * @brief Pack a altitudes message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param alt_gps GPS altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param alt_imu IMU altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_barometric barometeric altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_optical_flow Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_range_finder Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_extra Extra altitude above ground in meters, expressed as * 1000 (millimeters) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_altitudes_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDES_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, alt_gps); - _mav_put_int32_t(buf, 8, alt_imu); - _mav_put_int32_t(buf, 12, alt_barometric); - _mav_put_int32_t(buf, 16, alt_optical_flow); - _mav_put_int32_t(buf, 20, alt_range_finder); - _mav_put_int32_t(buf, 24, alt_extra); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDES_LEN); -#else - mavlink_altitudes_t packet; - packet.time_boot_ms = time_boot_ms; - packet.alt_gps = alt_gps; - packet.alt_imu = alt_imu; - packet.alt_barometric = alt_barometric; - packet.alt_optical_flow = alt_optical_flow; - packet.alt_range_finder = alt_range_finder; - packet.alt_extra = alt_extra; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDES_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ALTITUDES; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDES_LEN); -#endif -} - -/** - * @brief Pack a altitudes message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param alt_gps GPS altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param alt_imu IMU altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_barometric barometeric altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_optical_flow Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_range_finder Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_extra Extra altitude above ground in meters, expressed as * 1000 (millimeters) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_altitudes_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t time_boot_ms,int32_t alt_gps,int32_t alt_imu,int32_t alt_barometric,int32_t alt_optical_flow,int32_t alt_range_finder,int32_t alt_extra) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDES_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, alt_gps); - _mav_put_int32_t(buf, 8, alt_imu); - _mav_put_int32_t(buf, 12, alt_barometric); - _mav_put_int32_t(buf, 16, alt_optical_flow); - _mav_put_int32_t(buf, 20, alt_range_finder); - _mav_put_int32_t(buf, 24, alt_extra); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDES_LEN); -#else - mavlink_altitudes_t packet; - packet.time_boot_ms = time_boot_ms; - packet.alt_gps = alt_gps; - packet.alt_imu = alt_imu; - packet.alt_barometric = alt_barometric; - packet.alt_optical_flow = alt_optical_flow; - packet.alt_range_finder = alt_range_finder; - packet.alt_extra = alt_extra; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDES_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ALTITUDES; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDES_LEN); -#endif -} - -/** - * @brief Encode a altitudes struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param altitudes C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_altitudes_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitudes_t* altitudes) -{ - return mavlink_msg_altitudes_pack(system_id, component_id, msg, altitudes->time_boot_ms, altitudes->alt_gps, altitudes->alt_imu, altitudes->alt_barometric, altitudes->alt_optical_flow, altitudes->alt_range_finder, altitudes->alt_extra); -} - -/** - * @brief Encode a altitudes struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param altitudes C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_altitudes_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitudes_t* altitudes) -{ - return mavlink_msg_altitudes_pack_chan(system_id, component_id, chan, msg, altitudes->time_boot_ms, altitudes->alt_gps, altitudes->alt_imu, altitudes->alt_barometric, altitudes->alt_optical_flow, altitudes->alt_range_finder, altitudes->alt_extra); -} - -/** - * @brief Send a altitudes message - * @param chan MAVLink channel to send the message - * - * @param time_boot_ms Timestamp (milliseconds since system boot) - * @param alt_gps GPS altitude in meters, expressed as * 1000 (millimeters), above MSL - * @param alt_imu IMU altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_barometric barometeric altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_optical_flow Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_range_finder Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) - * @param alt_extra Extra altitude above ground in meters, expressed as * 1000 (millimeters) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_altitudes_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ALTITUDES_LEN]; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, alt_gps); - _mav_put_int32_t(buf, 8, alt_imu); - _mav_put_int32_t(buf, 12, alt_barometric); - _mav_put_int32_t(buf, 16, alt_optical_flow); - _mav_put_int32_t(buf, 20, alt_range_finder); - _mav_put_int32_t(buf, 24, alt_extra); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN); -#endif -#else - mavlink_altitudes_t packet; - packet.time_boot_ms = time_boot_ms; - packet.alt_gps = alt_gps; - packet.alt_imu = alt_imu; - packet.alt_barometric = alt_barometric; - packet.alt_optical_flow = alt_optical_flow; - packet.alt_range_finder = alt_range_finder; - packet.alt_extra = alt_extra; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDES_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_ALTITUDES_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_altitudes_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t alt_gps, int32_t alt_imu, int32_t alt_barometric, int32_t alt_optical_flow, int32_t alt_range_finder, int32_t alt_extra) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, time_boot_ms); - _mav_put_int32_t(buf, 4, alt_gps); - _mav_put_int32_t(buf, 8, alt_imu); - _mav_put_int32_t(buf, 12, alt_barometric); - _mav_put_int32_t(buf, 16, alt_optical_flow); - _mav_put_int32_t(buf, 20, alt_range_finder); - _mav_put_int32_t(buf, 24, alt_extra); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, buf, MAVLINK_MSG_ID_ALTITUDES_LEN); -#endif -#else - mavlink_altitudes_t *packet = (mavlink_altitudes_t *)msgbuf; - packet->time_boot_ms = time_boot_ms; - packet->alt_gps = alt_gps; - packet->alt_imu = alt_imu; - packet->alt_barometric = alt_barometric; - packet->alt_optical_flow = alt_optical_flow; - packet->alt_range_finder = alt_range_finder; - packet->alt_extra = alt_extra; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)packet, MAVLINK_MSG_ID_ALTITUDES_LEN, MAVLINK_MSG_ID_ALTITUDES_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDES, (const char *)packet, MAVLINK_MSG_ID_ALTITUDES_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE ALTITUDES UNPACKING - - -/** - * @brief Get field time_boot_ms from altitudes message - * - * @return Timestamp (milliseconds since system boot) - */ -static inline uint32_t mavlink_msg_altitudes_get_time_boot_ms(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field alt_gps from altitudes message - * - * @return GPS altitude in meters, expressed as * 1000 (millimeters), above MSL - */ -static inline int32_t mavlink_msg_altitudes_get_alt_gps(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field alt_imu from altitudes message - * - * @return IMU altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_altitudes_get_alt_imu(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field alt_barometric from altitudes message - * - * @return barometeric altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_altitudes_get_alt_barometric(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field alt_optical_flow from altitudes message - * - * @return Optical flow altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_altitudes_get_alt_optical_flow(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 16); -} - -/** - * @brief Get field alt_range_finder from altitudes message - * - * @return Rangefinder Altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_altitudes_get_alt_range_finder(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 20); -} - -/** - * @brief Get field alt_extra from altitudes message - * - * @return Extra altitude above ground in meters, expressed as * 1000 (millimeters) - */ -static inline int32_t mavlink_msg_altitudes_get_alt_extra(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 24); -} - -/** - * @brief Decode a altitudes message into a struct - * - * @param msg The message to decode - * @param altitudes C-struct to decode the message contents into - */ -static inline void mavlink_msg_altitudes_decode(const mavlink_message_t* msg, mavlink_altitudes_t* altitudes) -{ -#if MAVLINK_NEED_BYTE_SWAP - altitudes->time_boot_ms = mavlink_msg_altitudes_get_time_boot_ms(msg); - altitudes->alt_gps = mavlink_msg_altitudes_get_alt_gps(msg); - altitudes->alt_imu = mavlink_msg_altitudes_get_alt_imu(msg); - altitudes->alt_barometric = mavlink_msg_altitudes_get_alt_barometric(msg); - altitudes->alt_optical_flow = mavlink_msg_altitudes_get_alt_optical_flow(msg); - altitudes->alt_range_finder = mavlink_msg_altitudes_get_alt_range_finder(msg); - altitudes->alt_extra = mavlink_msg_altitudes_get_alt_extra(msg); -#else - memcpy(altitudes, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ALTITUDES_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h deleted file mode 100644 index e7b803a14..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function.h +++ /dev/null @@ -1,345 +0,0 @@ -// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION PACKING - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION 152 - -typedef struct __mavlink_flexifunction_buffer_function_t -{ - uint16_t func_index; ///< Function index - uint16_t func_count; ///< Total count of functions - uint16_t data_address; ///< Address in the flexifunction data, Set to 0xFFFF to use address in target memory - uint16_t data_size; ///< Size of the - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - int8_t data[48]; ///< Settings data -} mavlink_flexifunction_buffer_function_t; - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN 58 -#define MAVLINK_MSG_ID_152_LEN 58 - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC 101 -#define MAVLINK_MSG_ID_152_CRC 101 - -#define MAVLINK_MSG_FLEXIFUNCTION_BUFFER_FUNCTION_FIELD_DATA_LEN 48 - -#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_BUFFER_FUNCTION { \ - "FLEXIFUNCTION_BUFFER_FUNCTION", \ - 7, \ - { { "func_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_flexifunction_buffer_function_t, func_index) }, \ - { "func_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_flexifunction_buffer_function_t, func_count) }, \ - { "data_address", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_flexifunction_buffer_function_t, data_address) }, \ - { "data_size", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_flexifunction_buffer_function_t, data_size) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_flexifunction_buffer_function_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_flexifunction_buffer_function_t, target_component) }, \ - { "data", NULL, MAVLINK_TYPE_INT8_T, 48, 10, offsetof(mavlink_flexifunction_buffer_function_t, data) }, \ - } \ -} - - -/** - * @brief Pack a flexifunction_buffer_function message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param func_index Function index - * @param func_count Total count of functions - * @param data_address Address in the flexifunction data, Set to 0xFFFF to use address in target memory - * @param data_size Size of the - * @param data Settings data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t func_count, uint16_t data_address, uint16_t data_size, const int8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN]; - _mav_put_uint16_t(buf, 0, func_index); - _mav_put_uint16_t(buf, 2, func_count); - _mav_put_uint16_t(buf, 4, data_address); - _mav_put_uint16_t(buf, 6, data_size); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_int8_t_array(buf, 10, data, 48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#else - mavlink_flexifunction_buffer_function_t packet; - packet.func_index = func_index; - packet.func_count = func_count; - packet.data_address = data_address; - packet.data_size = data_size; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.data, data, sizeof(int8_t)*48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#endif -} - -/** - * @brief Pack a flexifunction_buffer_function message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param func_index Function index - * @param func_count Total count of functions - * @param data_address Address in the flexifunction data, Set to 0xFFFF to use address in target memory - * @param data_size Size of the - * @param data Settings data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t func_index,uint16_t func_count,uint16_t data_address,uint16_t data_size,const int8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN]; - _mav_put_uint16_t(buf, 0, func_index); - _mav_put_uint16_t(buf, 2, func_count); - _mav_put_uint16_t(buf, 4, data_address); - _mav_put_uint16_t(buf, 6, data_size); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_int8_t_array(buf, 10, data, 48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#else - mavlink_flexifunction_buffer_function_t packet; - packet.func_index = func_index; - packet.func_count = func_count; - packet.data_address = data_address; - packet.data_size = data_size; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.data, data, sizeof(int8_t)*48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#endif -} - -/** - * @brief Encode a flexifunction_buffer_function struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flexifunction_buffer_function C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_buffer_function_t* flexifunction_buffer_function) -{ - return mavlink_msg_flexifunction_buffer_function_pack(system_id, component_id, msg, flexifunction_buffer_function->target_system, flexifunction_buffer_function->target_component, flexifunction_buffer_function->func_index, flexifunction_buffer_function->func_count, flexifunction_buffer_function->data_address, flexifunction_buffer_function->data_size, flexifunction_buffer_function->data); -} - -/** - * @brief Encode a flexifunction_buffer_function struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flexifunction_buffer_function C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_buffer_function_t* flexifunction_buffer_function) -{ - return mavlink_msg_flexifunction_buffer_function_pack_chan(system_id, component_id, chan, msg, flexifunction_buffer_function->target_system, flexifunction_buffer_function->target_component, flexifunction_buffer_function->func_index, flexifunction_buffer_function->func_count, flexifunction_buffer_function->data_address, flexifunction_buffer_function->data_size, flexifunction_buffer_function->data); -} - -/** - * @brief Send a flexifunction_buffer_function message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param func_index Function index - * @param func_count Total count of functions - * @param data_address Address in the flexifunction data, Set to 0xFFFF to use address in target memory - * @param data_size Size of the - * @param data Settings data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flexifunction_buffer_function_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t func_count, uint16_t data_address, uint16_t data_size, const int8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN]; - _mav_put_uint16_t(buf, 0, func_index); - _mav_put_uint16_t(buf, 2, func_count); - _mav_put_uint16_t(buf, 4, data_address); - _mav_put_uint16_t(buf, 6, data_size); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_int8_t_array(buf, 10, data, 48); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#endif -#else - mavlink_flexifunction_buffer_function_t packet; - packet.func_index = func_index; - packet.func_count = func_count; - packet.data_address = data_address; - packet.data_size = data_size; - packet.target_system = target_system; - packet.target_component = target_component; - mav_array_memcpy(packet.data, data, sizeof(int8_t)*48); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flexifunction_buffer_function_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t func_count, uint16_t data_address, uint16_t data_size, const int8_t *data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, func_index); - _mav_put_uint16_t(buf, 2, func_count); - _mav_put_uint16_t(buf, 4, data_address); - _mav_put_uint16_t(buf, 6, data_size); - _mav_put_uint8_t(buf, 8, target_system); - _mav_put_uint8_t(buf, 9, target_component); - _mav_put_int8_t_array(buf, 10, data, 48); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#endif -#else - mavlink_flexifunction_buffer_function_t *packet = (mavlink_flexifunction_buffer_function_t *)msgbuf; - packet->func_index = func_index; - packet->func_count = func_count; - packet->data_address = data_address; - packet->data_size = data_size; - packet->target_system = target_system; - packet->target_component = target_component; - mav_array_memcpy(packet->data, data, sizeof(int8_t)*48); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION UNPACKING - - -/** - * @brief Get field target_system from flexifunction_buffer_function message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_flexifunction_buffer_function_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field target_component from flexifunction_buffer_function message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_flexifunction_buffer_function_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Get field func_index from flexifunction_buffer_function message - * - * @return Function index - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_func_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field func_count from flexifunction_buffer_function message - * - * @return Total count of functions - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_func_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field data_address from flexifunction_buffer_function message - * - * @return Address in the flexifunction data, Set to 0xFFFF to use address in target memory - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_data_address(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field data_size from flexifunction_buffer_function message - * - * @return Size of the - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_data_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field data from flexifunction_buffer_function message - * - * @return Settings data - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_get_data(const mavlink_message_t* msg, int8_t *data) -{ - return _MAV_RETURN_int8_t_array(msg, data, 48, 10); -} - -/** - * @brief Decode a flexifunction_buffer_function message into a struct - * - * @param msg The message to decode - * @param flexifunction_buffer_function C-struct to decode the message contents into - */ -static inline void mavlink_msg_flexifunction_buffer_function_decode(const mavlink_message_t* msg, mavlink_flexifunction_buffer_function_t* flexifunction_buffer_function) -{ -#if MAVLINK_NEED_BYTE_SWAP - flexifunction_buffer_function->func_index = mavlink_msg_flexifunction_buffer_function_get_func_index(msg); - flexifunction_buffer_function->func_count = mavlink_msg_flexifunction_buffer_function_get_func_count(msg); - flexifunction_buffer_function->data_address = mavlink_msg_flexifunction_buffer_function_get_data_address(msg); - flexifunction_buffer_function->data_size = mavlink_msg_flexifunction_buffer_function_get_data_size(msg); - flexifunction_buffer_function->target_system = mavlink_msg_flexifunction_buffer_function_get_target_system(msg); - flexifunction_buffer_function->target_component = mavlink_msg_flexifunction_buffer_function_get_target_component(msg); - mavlink_msg_flexifunction_buffer_function_get_data(msg, flexifunction_buffer_function->data); -#else - memcpy(flexifunction_buffer_function, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h deleted file mode 100644 index 06631b40e..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_buffer_function_ack.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION_ACK PACKING - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK 153 - -typedef struct __mavlink_flexifunction_buffer_function_ack_t -{ - uint16_t func_index; ///< Function index - uint16_t result; ///< result of acknowledge, 0=fail, 1=good - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_flexifunction_buffer_function_ack_t; - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN 6 -#define MAVLINK_MSG_ID_153_LEN 6 - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC 109 -#define MAVLINK_MSG_ID_153_CRC 109 - - - -#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_BUFFER_FUNCTION_ACK { \ - "FLEXIFUNCTION_BUFFER_FUNCTION_ACK", \ - 4, \ - { { "func_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_flexifunction_buffer_function_ack_t, func_index) }, \ - { "result", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_flexifunction_buffer_function_ack_t, result) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_flexifunction_buffer_function_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_flexifunction_buffer_function_ack_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a flexifunction_buffer_function_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param func_index Function index - * @param result result of acknowledge, 0=fail, 1=good - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN]; - _mav_put_uint16_t(buf, 0, func_index); - _mav_put_uint16_t(buf, 2, result); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#else - mavlink_flexifunction_buffer_function_ack_t packet; - packet.func_index = func_index; - packet.result = result; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#endif -} - -/** - * @brief Pack a flexifunction_buffer_function_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param func_index Function index - * @param result result of acknowledge, 0=fail, 1=good - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint16_t func_index,uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN]; - _mav_put_uint16_t(buf, 0, func_index); - _mav_put_uint16_t(buf, 2, result); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#else - mavlink_flexifunction_buffer_function_ack_t packet; - packet.func_index = func_index; - packet.result = result; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#endif -} - -/** - * @brief Encode a flexifunction_buffer_function_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flexifunction_buffer_function_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_buffer_function_ack_t* flexifunction_buffer_function_ack) -{ - return mavlink_msg_flexifunction_buffer_function_ack_pack(system_id, component_id, msg, flexifunction_buffer_function_ack->target_system, flexifunction_buffer_function_ack->target_component, flexifunction_buffer_function_ack->func_index, flexifunction_buffer_function_ack->result); -} - -/** - * @brief Encode a flexifunction_buffer_function_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flexifunction_buffer_function_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_buffer_function_ack_t* flexifunction_buffer_function_ack) -{ - return mavlink_msg_flexifunction_buffer_function_ack_pack_chan(system_id, component_id, chan, msg, flexifunction_buffer_function_ack->target_system, flexifunction_buffer_function_ack->target_component, flexifunction_buffer_function_ack->func_index, flexifunction_buffer_function_ack->result); -} - -/** - * @brief Send a flexifunction_buffer_function_ack message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param func_index Function index - * @param result result of acknowledge, 0=fail, 1=good - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flexifunction_buffer_function_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN]; - _mav_put_uint16_t(buf, 0, func_index); - _mav_put_uint16_t(buf, 2, result); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#endif -#else - mavlink_flexifunction_buffer_function_ack_t packet; - packet.func_index = func_index; - packet.result = result; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flexifunction_buffer_function_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t func_index, uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, func_index); - _mav_put_uint16_t(buf, 2, result); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#endif -#else - mavlink_flexifunction_buffer_function_ack_t *packet = (mavlink_flexifunction_buffer_function_ack_t *)msgbuf; - packet->func_index = func_index; - packet->result = result; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FLEXIFUNCTION_BUFFER_FUNCTION_ACK UNPACKING - - -/** - * @brief Get field target_system from flexifunction_buffer_function_ack message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_flexifunction_buffer_function_ack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from flexifunction_buffer_function_ack message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_flexifunction_buffer_function_ack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field func_index from flexifunction_buffer_function_ack message - * - * @return Function index - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_get_func_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field result from flexifunction_buffer_function_ack message - * - * @return result of acknowledge, 0=fail, 1=good - */ -static inline uint16_t mavlink_msg_flexifunction_buffer_function_ack_get_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a flexifunction_buffer_function_ack message into a struct - * - * @param msg The message to decode - * @param flexifunction_buffer_function_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_flexifunction_buffer_function_ack_decode(const mavlink_message_t* msg, mavlink_flexifunction_buffer_function_ack_t* flexifunction_buffer_function_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP - flexifunction_buffer_function_ack->func_index = mavlink_msg_flexifunction_buffer_function_ack_get_func_index(msg); - flexifunction_buffer_function_ack->result = mavlink_msg_flexifunction_buffer_function_ack_get_result(msg); - flexifunction_buffer_function_ack->target_system = mavlink_msg_flexifunction_buffer_function_ack_get_target_system(msg); - flexifunction_buffer_function_ack->target_component = mavlink_msg_flexifunction_buffer_function_ack_get_target_component(msg); -#else - memcpy(flexifunction_buffer_function_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_BUFFER_FUNCTION_ACK_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h deleted file mode 100644 index ac8366eef..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command.h +++ /dev/null @@ -1,257 +0,0 @@ -// MESSAGE FLEXIFUNCTION_COMMAND PACKING - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND 157 - -typedef struct __mavlink_flexifunction_command_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t command_type; ///< Flexifunction command type -} mavlink_flexifunction_command_t; - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN 3 -#define MAVLINK_MSG_ID_157_LEN 3 - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC 133 -#define MAVLINK_MSG_ID_157_CRC 133 - - - -#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_COMMAND { \ - "FLEXIFUNCTION_COMMAND", \ - 3, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_flexifunction_command_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_flexifunction_command_t, target_component) }, \ - { "command_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_flexifunction_command_t, command_type) }, \ - } \ -} - - -/** - * @brief Pack a flexifunction_command message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param command_type Flexifunction command type - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t command_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, command_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#else - mavlink_flexifunction_command_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.command_type = command_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#endif -} - -/** - * @brief Pack a flexifunction_command message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param command_type Flexifunction command type - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t command_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, command_type); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#else - mavlink_flexifunction_command_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.command_type = command_type; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#endif -} - -/** - * @brief Encode a flexifunction_command struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flexifunction_command C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_command_t* flexifunction_command) -{ - return mavlink_msg_flexifunction_command_pack(system_id, component_id, msg, flexifunction_command->target_system, flexifunction_command->target_component, flexifunction_command->command_type); -} - -/** - * @brief Encode a flexifunction_command struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flexifunction_command C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_command_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_command_t* flexifunction_command) -{ - return mavlink_msg_flexifunction_command_pack_chan(system_id, component_id, chan, msg, flexifunction_command->target_system, flexifunction_command->target_component, flexifunction_command->command_type); -} - -/** - * @brief Send a flexifunction_command message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param command_type Flexifunction command type - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flexifunction_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, command_type); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#endif -#else - mavlink_flexifunction_command_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.command_type = command_type; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flexifunction_command_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command_type) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, command_type); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#endif -#else - mavlink_flexifunction_command_t *packet = (mavlink_flexifunction_command_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->command_type = command_type; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FLEXIFUNCTION_COMMAND UNPACKING - - -/** - * @brief Get field target_system from flexifunction_command message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_flexifunction_command_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from flexifunction_command message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_flexifunction_command_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field command_type from flexifunction_command message - * - * @return Flexifunction command type - */ -static inline uint8_t mavlink_msg_flexifunction_command_get_command_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Decode a flexifunction_command message into a struct - * - * @param msg The message to decode - * @param flexifunction_command C-struct to decode the message contents into - */ -static inline void mavlink_msg_flexifunction_command_decode(const mavlink_message_t* msg, mavlink_flexifunction_command_t* flexifunction_command) -{ -#if MAVLINK_NEED_BYTE_SWAP - flexifunction_command->target_system = mavlink_msg_flexifunction_command_get_target_system(msg); - flexifunction_command->target_component = mavlink_msg_flexifunction_command_get_target_component(msg); - flexifunction_command->command_type = mavlink_msg_flexifunction_command_get_command_type(msg); -#else - memcpy(flexifunction_command, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h deleted file mode 100644 index c88e2dc39..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_command_ack.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE FLEXIFUNCTION_COMMAND_ACK PACKING - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK 158 - -typedef struct __mavlink_flexifunction_command_ack_t -{ - uint16_t command_type; ///< Command acknowledged - uint16_t result; ///< result of acknowledge -} mavlink_flexifunction_command_ack_t; - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN 4 -#define MAVLINK_MSG_ID_158_LEN 4 - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC 208 -#define MAVLINK_MSG_ID_158_CRC 208 - - - -#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_COMMAND_ACK { \ - "FLEXIFUNCTION_COMMAND_ACK", \ - 2, \ - { { "command_type", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_flexifunction_command_ack_t, command_type) }, \ - { "result", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_flexifunction_command_ack_t, result) }, \ - } \ -} - - -/** - * @brief Pack a flexifunction_command_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param command_type Command acknowledged - * @param result result of acknowledge - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t command_type, uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN]; - _mav_put_uint16_t(buf, 0, command_type); - _mav_put_uint16_t(buf, 2, result); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#else - mavlink_flexifunction_command_ack_t packet; - packet.command_type = command_type; - packet.result = result; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#endif -} - -/** - * @brief Pack a flexifunction_command_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param command_type Command acknowledged - * @param result result of acknowledge - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t command_type,uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN]; - _mav_put_uint16_t(buf, 0, command_type); - _mav_put_uint16_t(buf, 2, result); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#else - mavlink_flexifunction_command_ack_t packet; - packet.command_type = command_type; - packet.result = result; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#endif -} - -/** - * @brief Encode a flexifunction_command_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flexifunction_command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_command_ack_t* flexifunction_command_ack) -{ - return mavlink_msg_flexifunction_command_ack_pack(system_id, component_id, msg, flexifunction_command_ack->command_type, flexifunction_command_ack->result); -} - -/** - * @brief Encode a flexifunction_command_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flexifunction_command_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_command_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_command_ack_t* flexifunction_command_ack) -{ - return mavlink_msg_flexifunction_command_ack_pack_chan(system_id, component_id, chan, msg, flexifunction_command_ack->command_type, flexifunction_command_ack->result); -} - -/** - * @brief Send a flexifunction_command_ack message - * @param chan MAVLink channel to send the message - * - * @param command_type Command acknowledged - * @param result result of acknowledge - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flexifunction_command_ack_send(mavlink_channel_t chan, uint16_t command_type, uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN]; - _mav_put_uint16_t(buf, 0, command_type); - _mav_put_uint16_t(buf, 2, result); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#endif -#else - mavlink_flexifunction_command_ack_t packet; - packet.command_type = command_type; - packet.result = result; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flexifunction_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command_type, uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, command_type); - _mav_put_uint16_t(buf, 2, result); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#endif -#else - mavlink_flexifunction_command_ack_t *packet = (mavlink_flexifunction_command_ack_t *)msgbuf; - packet->command_type = command_type; - packet->result = result; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FLEXIFUNCTION_COMMAND_ACK UNPACKING - - -/** - * @brief Get field command_type from flexifunction_command_ack message - * - * @return Command acknowledged - */ -static inline uint16_t mavlink_msg_flexifunction_command_ack_get_command_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field result from flexifunction_command_ack message - * - * @return result of acknowledge - */ -static inline uint16_t mavlink_msg_flexifunction_command_ack_get_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a flexifunction_command_ack message into a struct - * - * @param msg The message to decode - * @param flexifunction_command_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_flexifunction_command_ack_decode(const mavlink_message_t* msg, mavlink_flexifunction_command_ack_t* flexifunction_command_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP - flexifunction_command_ack->command_type = mavlink_msg_flexifunction_command_ack_get_command_type(msg); - flexifunction_command_ack->result = mavlink_msg_flexifunction_command_ack_get_result(msg); -#else - memcpy(flexifunction_command_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_COMMAND_ACK_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h deleted file mode 100644 index 619f810c5..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory.h +++ /dev/null @@ -1,321 +0,0 @@ -// MESSAGE FLEXIFUNCTION_DIRECTORY PACKING - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY 155 - -typedef struct __mavlink_flexifunction_directory_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t directory_type; ///< 0=inputs, 1=outputs - uint8_t start_index; ///< index of first directory entry to write - uint8_t count; ///< count of directory entries to write - int8_t directory_data[48]; ///< Settings data -} mavlink_flexifunction_directory_t; - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN 53 -#define MAVLINK_MSG_ID_155_LEN 53 - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC 12 -#define MAVLINK_MSG_ID_155_CRC 12 - -#define MAVLINK_MSG_FLEXIFUNCTION_DIRECTORY_FIELD_DIRECTORY_DATA_LEN 48 - -#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_DIRECTORY { \ - "FLEXIFUNCTION_DIRECTORY", \ - 6, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_flexifunction_directory_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_flexifunction_directory_t, target_component) }, \ - { "directory_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_flexifunction_directory_t, directory_type) }, \ - { "start_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_flexifunction_directory_t, start_index) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_flexifunction_directory_t, count) }, \ - { "directory_data", NULL, MAVLINK_TYPE_INT8_T, 48, 5, offsetof(mavlink_flexifunction_directory_t, directory_data) }, \ - } \ -} - - -/** - * @brief Pack a flexifunction_directory message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param directory_type 0=inputs, 1=outputs - * @param start_index index of first directory entry to write - * @param count count of directory entries to write - * @param directory_data Settings data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_directory_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, const int8_t *directory_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, directory_type); - _mav_put_uint8_t(buf, 3, start_index); - _mav_put_uint8_t(buf, 4, count); - _mav_put_int8_t_array(buf, 5, directory_data, 48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#else - mavlink_flexifunction_directory_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.directory_type = directory_type; - packet.start_index = start_index; - packet.count = count; - mav_array_memcpy(packet.directory_data, directory_data, sizeof(int8_t)*48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#endif -} - -/** - * @brief Pack a flexifunction_directory message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param directory_type 0=inputs, 1=outputs - * @param start_index index of first directory entry to write - * @param count count of directory entries to write - * @param directory_data Settings data - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_directory_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t directory_type,uint8_t start_index,uint8_t count,const int8_t *directory_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, directory_type); - _mav_put_uint8_t(buf, 3, start_index); - _mav_put_uint8_t(buf, 4, count); - _mav_put_int8_t_array(buf, 5, directory_data, 48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#else - mavlink_flexifunction_directory_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.directory_type = directory_type; - packet.start_index = start_index; - packet.count = count; - mav_array_memcpy(packet.directory_data, directory_data, sizeof(int8_t)*48); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#endif -} - -/** - * @brief Encode a flexifunction_directory struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flexifunction_directory C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_directory_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_directory_t* flexifunction_directory) -{ - return mavlink_msg_flexifunction_directory_pack(system_id, component_id, msg, flexifunction_directory->target_system, flexifunction_directory->target_component, flexifunction_directory->directory_type, flexifunction_directory->start_index, flexifunction_directory->count, flexifunction_directory->directory_data); -} - -/** - * @brief Encode a flexifunction_directory struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flexifunction_directory C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_directory_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_directory_t* flexifunction_directory) -{ - return mavlink_msg_flexifunction_directory_pack_chan(system_id, component_id, chan, msg, flexifunction_directory->target_system, flexifunction_directory->target_component, flexifunction_directory->directory_type, flexifunction_directory->start_index, flexifunction_directory->count, flexifunction_directory->directory_data); -} - -/** - * @brief Send a flexifunction_directory message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param directory_type 0=inputs, 1=outputs - * @param start_index index of first directory entry to write - * @param count count of directory entries to write - * @param directory_data Settings data - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flexifunction_directory_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, const int8_t *directory_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, directory_type); - _mav_put_uint8_t(buf, 3, start_index); - _mav_put_uint8_t(buf, 4, count); - _mav_put_int8_t_array(buf, 5, directory_data, 48); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#endif -#else - mavlink_flexifunction_directory_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - packet.directory_type = directory_type; - packet.start_index = start_index; - packet.count = count; - mav_array_memcpy(packet.directory_data, directory_data, sizeof(int8_t)*48); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flexifunction_directory_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, const int8_t *directory_data) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - _mav_put_uint8_t(buf, 2, directory_type); - _mav_put_uint8_t(buf, 3, start_index); - _mav_put_uint8_t(buf, 4, count); - _mav_put_int8_t_array(buf, 5, directory_data, 48); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#endif -#else - mavlink_flexifunction_directory_t *packet = (mavlink_flexifunction_directory_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - packet->directory_type = directory_type; - packet->start_index = start_index; - packet->count = count; - mav_array_memcpy(packet->directory_data, directory_data, sizeof(int8_t)*48); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FLEXIFUNCTION_DIRECTORY UNPACKING - - -/** - * @brief Get field target_system from flexifunction_directory message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_flexifunction_directory_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from flexifunction_directory message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_flexifunction_directory_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field directory_type from flexifunction_directory message - * - * @return 0=inputs, 1=outputs - */ -static inline uint8_t mavlink_msg_flexifunction_directory_get_directory_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field start_index from flexifunction_directory message - * - * @return index of first directory entry to write - */ -static inline uint8_t mavlink_msg_flexifunction_directory_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field count from flexifunction_directory message - * - * @return count of directory entries to write - */ -static inline uint8_t mavlink_msg_flexifunction_directory_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field directory_data from flexifunction_directory message - * - * @return Settings data - */ -static inline uint16_t mavlink_msg_flexifunction_directory_get_directory_data(const mavlink_message_t* msg, int8_t *directory_data) -{ - return _MAV_RETURN_int8_t_array(msg, directory_data, 48, 5); -} - -/** - * @brief Decode a flexifunction_directory message into a struct - * - * @param msg The message to decode - * @param flexifunction_directory C-struct to decode the message contents into - */ -static inline void mavlink_msg_flexifunction_directory_decode(const mavlink_message_t* msg, mavlink_flexifunction_directory_t* flexifunction_directory) -{ -#if MAVLINK_NEED_BYTE_SWAP - flexifunction_directory->target_system = mavlink_msg_flexifunction_directory_get_target_system(msg); - flexifunction_directory->target_component = mavlink_msg_flexifunction_directory_get_target_component(msg); - flexifunction_directory->directory_type = mavlink_msg_flexifunction_directory_get_directory_type(msg); - flexifunction_directory->start_index = mavlink_msg_flexifunction_directory_get_start_index(msg); - flexifunction_directory->count = mavlink_msg_flexifunction_directory_get_count(msg); - mavlink_msg_flexifunction_directory_get_directory_data(msg, flexifunction_directory->directory_data); -#else - memcpy(flexifunction_directory, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h deleted file mode 100644 index 0287183d8..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_directory_ack.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE FLEXIFUNCTION_DIRECTORY_ACK PACKING - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK 156 - -typedef struct __mavlink_flexifunction_directory_ack_t -{ - uint16_t result; ///< result of acknowledge, 0=fail, 1=good - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID - uint8_t directory_type; ///< 0=inputs, 1=outputs - uint8_t start_index; ///< index of first directory entry to write - uint8_t count; ///< count of directory entries to write -} mavlink_flexifunction_directory_ack_t; - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN 7 -#define MAVLINK_MSG_ID_156_LEN 7 - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC 218 -#define MAVLINK_MSG_ID_156_CRC 218 - - - -#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_DIRECTORY_ACK { \ - "FLEXIFUNCTION_DIRECTORY_ACK", \ - 6, \ - { { "result", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_flexifunction_directory_ack_t, result) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_flexifunction_directory_ack_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_flexifunction_directory_ack_t, target_component) }, \ - { "directory_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_flexifunction_directory_ack_t, directory_type) }, \ - { "start_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_flexifunction_directory_ack_t, start_index) }, \ - { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_flexifunction_directory_ack_t, count) }, \ - } \ -} - - -/** - * @brief Pack a flexifunction_directory_ack message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param directory_type 0=inputs, 1=outputs - * @param start_index index of first directory entry to write - * @param count count of directory entries to write - * @param result result of acknowledge, 0=fail, 1=good - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN]; - _mav_put_uint16_t(buf, 0, result); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, directory_type); - _mav_put_uint8_t(buf, 5, start_index); - _mav_put_uint8_t(buf, 6, count); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#else - mavlink_flexifunction_directory_ack_t packet; - packet.result = result; - packet.target_system = target_system; - packet.target_component = target_component; - packet.directory_type = directory_type; - packet.start_index = start_index; - packet.count = count; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#endif -} - -/** - * @brief Pack a flexifunction_directory_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param directory_type 0=inputs, 1=outputs - * @param start_index index of first directory entry to write - * @param count count of directory entries to write - * @param result result of acknowledge, 0=fail, 1=good - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_directory_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,uint8_t directory_type,uint8_t start_index,uint8_t count,uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN]; - _mav_put_uint16_t(buf, 0, result); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, directory_type); - _mav_put_uint8_t(buf, 5, start_index); - _mav_put_uint8_t(buf, 6, count); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#else - mavlink_flexifunction_directory_ack_t packet; - packet.result = result; - packet.target_system = target_system; - packet.target_component = target_component; - packet.directory_type = directory_type; - packet.start_index = start_index; - packet.count = count; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#endif -} - -/** - * @brief Encode a flexifunction_directory_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flexifunction_directory_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_directory_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_directory_ack_t* flexifunction_directory_ack) -{ - return mavlink_msg_flexifunction_directory_ack_pack(system_id, component_id, msg, flexifunction_directory_ack->target_system, flexifunction_directory_ack->target_component, flexifunction_directory_ack->directory_type, flexifunction_directory_ack->start_index, flexifunction_directory_ack->count, flexifunction_directory_ack->result); -} - -/** - * @brief Encode a flexifunction_directory_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flexifunction_directory_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_directory_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_directory_ack_t* flexifunction_directory_ack) -{ - return mavlink_msg_flexifunction_directory_ack_pack_chan(system_id, component_id, chan, msg, flexifunction_directory_ack->target_system, flexifunction_directory_ack->target_component, flexifunction_directory_ack->directory_type, flexifunction_directory_ack->start_index, flexifunction_directory_ack->count, flexifunction_directory_ack->result); -} - -/** - * @brief Send a flexifunction_directory_ack message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param directory_type 0=inputs, 1=outputs - * @param start_index index of first directory entry to write - * @param count count of directory entries to write - * @param result result of acknowledge, 0=fail, 1=good - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flexifunction_directory_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN]; - _mav_put_uint16_t(buf, 0, result); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, directory_type); - _mav_put_uint8_t(buf, 5, start_index); - _mav_put_uint8_t(buf, 6, count); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#endif -#else - mavlink_flexifunction_directory_ack_t packet; - packet.result = result; - packet.target_system = target_system; - packet.target_component = target_component; - packet.directory_type = directory_type; - packet.start_index = start_index; - packet.count = count; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flexifunction_directory_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t directory_type, uint8_t start_index, uint8_t count, uint16_t result) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, result); - _mav_put_uint8_t(buf, 2, target_system); - _mav_put_uint8_t(buf, 3, target_component); - _mav_put_uint8_t(buf, 4, directory_type); - _mav_put_uint8_t(buf, 5, start_index); - _mav_put_uint8_t(buf, 6, count); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#endif -#else - mavlink_flexifunction_directory_ack_t *packet = (mavlink_flexifunction_directory_ack_t *)msgbuf; - packet->result = result; - packet->target_system = target_system; - packet->target_component = target_component; - packet->directory_type = directory_type; - packet->start_index = start_index; - packet->count = count; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FLEXIFUNCTION_DIRECTORY_ACK UNPACKING - - -/** - * @brief Get field target_system from flexifunction_directory_ack message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field target_component from flexifunction_directory_ack message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field directory_type from flexifunction_directory_ack message - * - * @return 0=inputs, 1=outputs - */ -static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_directory_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field start_index from flexifunction_directory_ack message - * - * @return index of first directory entry to write - */ -static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_start_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field count from flexifunction_directory_ack message - * - * @return count of directory entries to write - */ -static inline uint8_t mavlink_msg_flexifunction_directory_ack_get_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field result from flexifunction_directory_ack message - * - * @return result of acknowledge, 0=fail, 1=good - */ -static inline uint16_t mavlink_msg_flexifunction_directory_ack_get_result(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Decode a flexifunction_directory_ack message into a struct - * - * @param msg The message to decode - * @param flexifunction_directory_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_flexifunction_directory_ack_decode(const mavlink_message_t* msg, mavlink_flexifunction_directory_ack_t* flexifunction_directory_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP - flexifunction_directory_ack->result = mavlink_msg_flexifunction_directory_ack_get_result(msg); - flexifunction_directory_ack->target_system = mavlink_msg_flexifunction_directory_ack_get_target_system(msg); - flexifunction_directory_ack->target_component = mavlink_msg_flexifunction_directory_ack_get_target_component(msg); - flexifunction_directory_ack->directory_type = mavlink_msg_flexifunction_directory_ack_get_directory_type(msg); - flexifunction_directory_ack->start_index = mavlink_msg_flexifunction_directory_ack_get_start_index(msg); - flexifunction_directory_ack->count = mavlink_msg_flexifunction_directory_ack_get_count(msg); -#else - memcpy(flexifunction_directory_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_DIRECTORY_ACK_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h deleted file mode 100644 index 570782e79..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_read_req.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE FLEXIFUNCTION_READ_REQ PACKING - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ 151 - -typedef struct __mavlink_flexifunction_read_req_t -{ - int16_t read_req_type; ///< Type of flexifunction data requested - int16_t data_index; ///< index into data where needed - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_flexifunction_read_req_t; - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN 6 -#define MAVLINK_MSG_ID_151_LEN 6 - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC 26 -#define MAVLINK_MSG_ID_151_CRC 26 - - - -#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_READ_REQ { \ - "FLEXIFUNCTION_READ_REQ", \ - 4, \ - { { "read_req_type", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_flexifunction_read_req_t, read_req_type) }, \ - { "data_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_flexifunction_read_req_t, data_index) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_flexifunction_read_req_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_flexifunction_read_req_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a flexifunction_read_req message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param read_req_type Type of flexifunction data requested - * @param data_index index into data where needed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_read_req_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, int16_t read_req_type, int16_t data_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN]; - _mav_put_int16_t(buf, 0, read_req_type); - _mav_put_int16_t(buf, 2, data_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#else - mavlink_flexifunction_read_req_t packet; - packet.read_req_type = read_req_type; - packet.data_index = data_index; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#endif -} - -/** - * @brief Pack a flexifunction_read_req message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param read_req_type Type of flexifunction data requested - * @param data_index index into data where needed - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_read_req_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,int16_t read_req_type,int16_t data_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN]; - _mav_put_int16_t(buf, 0, read_req_type); - _mav_put_int16_t(buf, 2, data_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#else - mavlink_flexifunction_read_req_t packet; - packet.read_req_type = read_req_type; - packet.data_index = data_index; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#endif -} - -/** - * @brief Encode a flexifunction_read_req struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flexifunction_read_req C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_read_req_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_read_req_t* flexifunction_read_req) -{ - return mavlink_msg_flexifunction_read_req_pack(system_id, component_id, msg, flexifunction_read_req->target_system, flexifunction_read_req->target_component, flexifunction_read_req->read_req_type, flexifunction_read_req->data_index); -} - -/** - * @brief Encode a flexifunction_read_req struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flexifunction_read_req C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_read_req_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_read_req_t* flexifunction_read_req) -{ - return mavlink_msg_flexifunction_read_req_pack_chan(system_id, component_id, chan, msg, flexifunction_read_req->target_system, flexifunction_read_req->target_component, flexifunction_read_req->read_req_type, flexifunction_read_req->data_index); -} - -/** - * @brief Send a flexifunction_read_req message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param read_req_type Type of flexifunction data requested - * @param data_index index into data where needed - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flexifunction_read_req_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t read_req_type, int16_t data_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN]; - _mav_put_int16_t(buf, 0, read_req_type); - _mav_put_int16_t(buf, 2, data_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#endif -#else - mavlink_flexifunction_read_req_t packet; - packet.read_req_type = read_req_type; - packet.data_index = data_index; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flexifunction_read_req_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t read_req_type, int16_t data_index) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int16_t(buf, 0, read_req_type); - _mav_put_int16_t(buf, 2, data_index); - _mav_put_uint8_t(buf, 4, target_system); - _mav_put_uint8_t(buf, 5, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#endif -#else - mavlink_flexifunction_read_req_t *packet = (mavlink_flexifunction_read_req_t *)msgbuf; - packet->read_req_type = read_req_type; - packet->data_index = data_index; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FLEXIFUNCTION_READ_REQ UNPACKING - - -/** - * @brief Get field target_system from flexifunction_read_req message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_flexifunction_read_req_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field target_component from flexifunction_read_req message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_flexifunction_read_req_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field read_req_type from flexifunction_read_req message - * - * @return Type of flexifunction data requested - */ -static inline int16_t mavlink_msg_flexifunction_read_req_get_read_req_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 0); -} - -/** - * @brief Get field data_index from flexifunction_read_req message - * - * @return index into data where needed - */ -static inline int16_t mavlink_msg_flexifunction_read_req_get_data_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 2); -} - -/** - * @brief Decode a flexifunction_read_req message into a struct - * - * @param msg The message to decode - * @param flexifunction_read_req C-struct to decode the message contents into - */ -static inline void mavlink_msg_flexifunction_read_req_decode(const mavlink_message_t* msg, mavlink_flexifunction_read_req_t* flexifunction_read_req) -{ -#if MAVLINK_NEED_BYTE_SWAP - flexifunction_read_req->read_req_type = mavlink_msg_flexifunction_read_req_get_read_req_type(msg); - flexifunction_read_req->data_index = mavlink_msg_flexifunction_read_req_get_data_index(msg); - flexifunction_read_req->target_system = mavlink_msg_flexifunction_read_req_get_target_system(msg); - flexifunction_read_req->target_component = mavlink_msg_flexifunction_read_req_get_target_component(msg); -#else - memcpy(flexifunction_read_req, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_READ_REQ_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h deleted file mode 100644 index c10000640..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_flexifunction_set.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE FLEXIFUNCTION_SET PACKING - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_SET 150 - -typedef struct __mavlink_flexifunction_set_t -{ - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_flexifunction_set_t; - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN 2 -#define MAVLINK_MSG_ID_150_LEN 2 - -#define MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC 181 -#define MAVLINK_MSG_ID_150_CRC 181 - - - -#define MAVLINK_MESSAGE_INFO_FLEXIFUNCTION_SET { \ - "FLEXIFUNCTION_SET", \ - 2, \ - { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_flexifunction_set_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_flexifunction_set_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a flexifunction_set message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#else - mavlink_flexifunction_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_SET; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#endif -} - -/** - * @brief Pack a flexifunction_set message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_flexifunction_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#else - mavlink_flexifunction_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FLEXIFUNCTION_SET; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#endif -} - -/** - * @brief Encode a flexifunction_set struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param flexifunction_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flexifunction_set_t* flexifunction_set) -{ - return mavlink_msg_flexifunction_set_pack(system_id, component_id, msg, flexifunction_set->target_system, flexifunction_set->target_component); -} - -/** - * @brief Encode a flexifunction_set struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param flexifunction_set C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_flexifunction_set_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flexifunction_set_t* flexifunction_set) -{ - return mavlink_msg_flexifunction_set_pack_chan(system_id, component_id, chan, msg, flexifunction_set->target_system, flexifunction_set->target_component); -} - -/** - * @brief Send a flexifunction_set message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_flexifunction_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN]; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#endif -#else - mavlink_flexifunction_set_t packet; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)&packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_flexifunction_set_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, target_system); - _mav_put_uint8_t(buf, 1, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, buf, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#endif -#else - mavlink_flexifunction_set_t *packet = (mavlink_flexifunction_set_t *)msgbuf; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLEXIFUNCTION_SET, (const char *)packet, MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FLEXIFUNCTION_SET UNPACKING - - -/** - * @brief Get field target_system from flexifunction_set message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_flexifunction_set_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field target_component from flexifunction_set message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_flexifunction_set_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Decode a flexifunction_set message into a struct - * - * @param msg The message to decode - * @param flexifunction_set C-struct to decode the message contents into - */ -static inline void mavlink_msg_flexifunction_set_decode(const mavlink_message_t* msg, mavlink_flexifunction_set_t* flexifunction_set) -{ -#if MAVLINK_NEED_BYTE_SWAP - flexifunction_set->target_system = mavlink_msg_flexifunction_set_get_target_system(msg); - flexifunction_set->target_component = mavlink_msg_flexifunction_set_get_target_component(msg); -#else - memcpy(flexifunction_set, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FLEXIFUNCTION_SET_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h deleted file mode 100644 index bbb753a06..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f13.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F13 PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13 177 - -typedef struct __mavlink_serial_udb_extra_f13_t -{ - int32_t sue_lat_origin; ///< Serial UDB Extra MP Origin Latitude - int32_t sue_lon_origin; ///< Serial UDB Extra MP Origin Longitude - int32_t sue_alt_origin; ///< Serial UDB Extra MP Origin Altitude Above Sea Level - int16_t sue_week_no; ///< Serial UDB Extra GPS Week Number -} mavlink_serial_udb_extra_f13_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN 14 -#define MAVLINK_MSG_ID_177_LEN 14 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC 249 -#define MAVLINK_MSG_ID_177_CRC 249 - - - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F13 { \ - "SERIAL_UDB_EXTRA_F13", \ - 4, \ - { { "sue_lat_origin", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_serial_udb_extra_f13_t, sue_lat_origin) }, \ - { "sue_lon_origin", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_serial_udb_extra_f13_t, sue_lon_origin) }, \ - { "sue_alt_origin", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_serial_udb_extra_f13_t, sue_alt_origin) }, \ - { "sue_week_no", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_serial_udb_extra_f13_t, sue_week_no) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f13 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_week_no Serial UDB Extra GPS Week Number - * @param sue_lat_origin Serial UDB Extra MP Origin Latitude - * @param sue_lon_origin Serial UDB Extra MP Origin Longitude - * @param sue_alt_origin Serial UDB Extra MP Origin Altitude Above Sea Level - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int16_t sue_week_no, int32_t sue_lat_origin, int32_t sue_lon_origin, int32_t sue_alt_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN]; - _mav_put_int32_t(buf, 0, sue_lat_origin); - _mav_put_int32_t(buf, 4, sue_lon_origin); - _mav_put_int32_t(buf, 8, sue_alt_origin); - _mav_put_int16_t(buf, 12, sue_week_no); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#else - mavlink_serial_udb_extra_f13_t packet; - packet.sue_lat_origin = sue_lat_origin; - packet.sue_lon_origin = sue_lon_origin; - packet.sue_alt_origin = sue_alt_origin; - packet.sue_week_no = sue_week_no; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f13 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_week_no Serial UDB Extra GPS Week Number - * @param sue_lat_origin Serial UDB Extra MP Origin Latitude - * @param sue_lon_origin Serial UDB Extra MP Origin Longitude - * @param sue_alt_origin Serial UDB Extra MP Origin Altitude Above Sea Level - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f13_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int16_t sue_week_no,int32_t sue_lat_origin,int32_t sue_lon_origin,int32_t sue_alt_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN]; - _mav_put_int32_t(buf, 0, sue_lat_origin); - _mav_put_int32_t(buf, 4, sue_lon_origin); - _mav_put_int32_t(buf, 8, sue_alt_origin); - _mav_put_int16_t(buf, 12, sue_week_no); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#else - mavlink_serial_udb_extra_f13_t packet; - packet.sue_lat_origin = sue_lat_origin; - packet.sue_lon_origin = sue_lon_origin; - packet.sue_alt_origin = sue_alt_origin; - packet.sue_week_no = sue_week_no; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f13 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f13 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f13_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f13_t* serial_udb_extra_f13) -{ - return mavlink_msg_serial_udb_extra_f13_pack(system_id, component_id, msg, serial_udb_extra_f13->sue_week_no, serial_udb_extra_f13->sue_lat_origin, serial_udb_extra_f13->sue_lon_origin, serial_udb_extra_f13->sue_alt_origin); -} - -/** - * @brief Encode a serial_udb_extra_f13 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f13 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f13_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f13_t* serial_udb_extra_f13) -{ - return mavlink_msg_serial_udb_extra_f13_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f13->sue_week_no, serial_udb_extra_f13->sue_lat_origin, serial_udb_extra_f13->sue_lon_origin, serial_udb_extra_f13->sue_alt_origin); -} - -/** - * @brief Send a serial_udb_extra_f13 message - * @param chan MAVLink channel to send the message - * - * @param sue_week_no Serial UDB Extra GPS Week Number - * @param sue_lat_origin Serial UDB Extra MP Origin Latitude - * @param sue_lon_origin Serial UDB Extra MP Origin Longitude - * @param sue_alt_origin Serial UDB Extra MP Origin Altitude Above Sea Level - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f13_send(mavlink_channel_t chan, int16_t sue_week_no, int32_t sue_lat_origin, int32_t sue_lon_origin, int32_t sue_alt_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN]; - _mav_put_int32_t(buf, 0, sue_lat_origin); - _mav_put_int32_t(buf, 4, sue_lon_origin); - _mav_put_int32_t(buf, 8, sue_alt_origin); - _mav_put_int16_t(buf, 12, sue_week_no); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#endif -#else - mavlink_serial_udb_extra_f13_t packet; - packet.sue_lat_origin = sue_lat_origin; - packet.sue_lon_origin = sue_lon_origin; - packet.sue_alt_origin = sue_alt_origin; - packet.sue_week_no = sue_week_no; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f13_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int16_t sue_week_no, int32_t sue_lat_origin, int32_t sue_lon_origin, int32_t sue_alt_origin) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, sue_lat_origin); - _mav_put_int32_t(buf, 4, sue_lon_origin); - _mav_put_int32_t(buf, 8, sue_alt_origin); - _mav_put_int16_t(buf, 12, sue_week_no); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#endif -#else - mavlink_serial_udb_extra_f13_t *packet = (mavlink_serial_udb_extra_f13_t *)msgbuf; - packet->sue_lat_origin = sue_lat_origin; - packet->sue_lon_origin = sue_lon_origin; - packet->sue_alt_origin = sue_alt_origin; - packet->sue_week_no = sue_week_no; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F13 UNPACKING - - -/** - * @brief Get field sue_week_no from serial_udb_extra_f13 message - * - * @return Serial UDB Extra GPS Week Number - */ -static inline int16_t mavlink_msg_serial_udb_extra_f13_get_sue_week_no(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field sue_lat_origin from serial_udb_extra_f13 message - * - * @return Serial UDB Extra MP Origin Latitude - */ -static inline int32_t mavlink_msg_serial_udb_extra_f13_get_sue_lat_origin(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field sue_lon_origin from serial_udb_extra_f13 message - * - * @return Serial UDB Extra MP Origin Longitude - */ -static inline int32_t mavlink_msg_serial_udb_extra_f13_get_sue_lon_origin(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field sue_alt_origin from serial_udb_extra_f13 message - * - * @return Serial UDB Extra MP Origin Altitude Above Sea Level - */ -static inline int32_t mavlink_msg_serial_udb_extra_f13_get_sue_alt_origin(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Decode a serial_udb_extra_f13 message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f13 C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f13_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f13_t* serial_udb_extra_f13) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_udb_extra_f13->sue_lat_origin = mavlink_msg_serial_udb_extra_f13_get_sue_lat_origin(msg); - serial_udb_extra_f13->sue_lon_origin = mavlink_msg_serial_udb_extra_f13_get_sue_lon_origin(msg); - serial_udb_extra_f13->sue_alt_origin = mavlink_msg_serial_udb_extra_f13_get_sue_alt_origin(msg); - serial_udb_extra_f13->sue_week_no = mavlink_msg_serial_udb_extra_f13_get_sue_week_no(msg); -#else - memcpy(serial_udb_extra_f13, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F13_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h deleted file mode 100644 index 112564d00..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f14.h +++ /dev/null @@ -1,449 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F14 PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14 178 - -typedef struct __mavlink_serial_udb_extra_f14_t -{ - uint32_t sue_TRAP_SOURCE; ///< Serial UDB Extra Type Program Address of Last Trap - int16_t sue_RCON; ///< Serial UDB Extra Reboot Regitster of DSPIC - int16_t sue_TRAP_FLAGS; ///< Serial UDB Extra Last dspic Trap Flags - int16_t sue_osc_fail_count; ///< Serial UDB Extra Number of Ocillator Failures - uint8_t sue_WIND_ESTIMATION; ///< Serial UDB Extra Wind Estimation Enabled - uint8_t sue_GPS_TYPE; ///< Serial UDB Extra Type of GPS Unit - uint8_t sue_DR; ///< Serial UDB Extra Dead Reckoning Enabled - uint8_t sue_BOARD_TYPE; ///< Serial UDB Extra Type of UDB Hardware - uint8_t sue_AIRFRAME; ///< Serial UDB Extra Type of Airframe - uint8_t sue_CLOCK_CONFIG; ///< Serial UDB Extra UDB Internal Clock Configuration - uint8_t sue_FLIGHT_PLAN_TYPE; ///< Serial UDB Extra Type of Flight Plan -} mavlink_serial_udb_extra_f14_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN 17 -#define MAVLINK_MSG_ID_178_LEN 17 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC 123 -#define MAVLINK_MSG_ID_178_CRC 123 - - - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F14 { \ - "SERIAL_UDB_EXTRA_F14", \ - 11, \ - { { "sue_TRAP_SOURCE", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_udb_extra_f14_t, sue_TRAP_SOURCE) }, \ - { "sue_RCON", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_serial_udb_extra_f14_t, sue_RCON) }, \ - { "sue_TRAP_FLAGS", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_serial_udb_extra_f14_t, sue_TRAP_FLAGS) }, \ - { "sue_osc_fail_count", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_serial_udb_extra_f14_t, sue_osc_fail_count) }, \ - { "sue_WIND_ESTIMATION", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_serial_udb_extra_f14_t, sue_WIND_ESTIMATION) }, \ - { "sue_GPS_TYPE", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_serial_udb_extra_f14_t, sue_GPS_TYPE) }, \ - { "sue_DR", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_serial_udb_extra_f14_t, sue_DR) }, \ - { "sue_BOARD_TYPE", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_serial_udb_extra_f14_t, sue_BOARD_TYPE) }, \ - { "sue_AIRFRAME", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_serial_udb_extra_f14_t, sue_AIRFRAME) }, \ - { "sue_CLOCK_CONFIG", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_serial_udb_extra_f14_t, sue_CLOCK_CONFIG) }, \ - { "sue_FLIGHT_PLAN_TYPE", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_serial_udb_extra_f14_t, sue_FLIGHT_PLAN_TYPE) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f14 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_WIND_ESTIMATION Serial UDB Extra Wind Estimation Enabled - * @param sue_GPS_TYPE Serial UDB Extra Type of GPS Unit - * @param sue_DR Serial UDB Extra Dead Reckoning Enabled - * @param sue_BOARD_TYPE Serial UDB Extra Type of UDB Hardware - * @param sue_AIRFRAME Serial UDB Extra Type of Airframe - * @param sue_RCON Serial UDB Extra Reboot Regitster of DSPIC - * @param sue_TRAP_FLAGS Serial UDB Extra Last dspic Trap Flags - * @param sue_TRAP_SOURCE Serial UDB Extra Type Program Address of Last Trap - * @param sue_osc_fail_count Serial UDB Extra Number of Ocillator Failures - * @param sue_CLOCK_CONFIG Serial UDB Extra UDB Internal Clock Configuration - * @param sue_FLIGHT_PLAN_TYPE Serial UDB Extra Type of Flight Plan - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t sue_WIND_ESTIMATION, uint8_t sue_GPS_TYPE, uint8_t sue_DR, uint8_t sue_BOARD_TYPE, uint8_t sue_AIRFRAME, int16_t sue_RCON, int16_t sue_TRAP_FLAGS, uint32_t sue_TRAP_SOURCE, int16_t sue_osc_fail_count, uint8_t sue_CLOCK_CONFIG, uint8_t sue_FLIGHT_PLAN_TYPE) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN]; - _mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE); - _mav_put_int16_t(buf, 4, sue_RCON); - _mav_put_int16_t(buf, 6, sue_TRAP_FLAGS); - _mav_put_int16_t(buf, 8, sue_osc_fail_count); - _mav_put_uint8_t(buf, 10, sue_WIND_ESTIMATION); - _mav_put_uint8_t(buf, 11, sue_GPS_TYPE); - _mav_put_uint8_t(buf, 12, sue_DR); - _mav_put_uint8_t(buf, 13, sue_BOARD_TYPE); - _mav_put_uint8_t(buf, 14, sue_AIRFRAME); - _mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG); - _mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#else - mavlink_serial_udb_extra_f14_t packet; - packet.sue_TRAP_SOURCE = sue_TRAP_SOURCE; - packet.sue_RCON = sue_RCON; - packet.sue_TRAP_FLAGS = sue_TRAP_FLAGS; - packet.sue_osc_fail_count = sue_osc_fail_count; - packet.sue_WIND_ESTIMATION = sue_WIND_ESTIMATION; - packet.sue_GPS_TYPE = sue_GPS_TYPE; - packet.sue_DR = sue_DR; - packet.sue_BOARD_TYPE = sue_BOARD_TYPE; - packet.sue_AIRFRAME = sue_AIRFRAME; - packet.sue_CLOCK_CONFIG = sue_CLOCK_CONFIG; - packet.sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f14 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_WIND_ESTIMATION Serial UDB Extra Wind Estimation Enabled - * @param sue_GPS_TYPE Serial UDB Extra Type of GPS Unit - * @param sue_DR Serial UDB Extra Dead Reckoning Enabled - * @param sue_BOARD_TYPE Serial UDB Extra Type of UDB Hardware - * @param sue_AIRFRAME Serial UDB Extra Type of Airframe - * @param sue_RCON Serial UDB Extra Reboot Regitster of DSPIC - * @param sue_TRAP_FLAGS Serial UDB Extra Last dspic Trap Flags - * @param sue_TRAP_SOURCE Serial UDB Extra Type Program Address of Last Trap - * @param sue_osc_fail_count Serial UDB Extra Number of Ocillator Failures - * @param sue_CLOCK_CONFIG Serial UDB Extra UDB Internal Clock Configuration - * @param sue_FLIGHT_PLAN_TYPE Serial UDB Extra Type of Flight Plan - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f14_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t sue_WIND_ESTIMATION,uint8_t sue_GPS_TYPE,uint8_t sue_DR,uint8_t sue_BOARD_TYPE,uint8_t sue_AIRFRAME,int16_t sue_RCON,int16_t sue_TRAP_FLAGS,uint32_t sue_TRAP_SOURCE,int16_t sue_osc_fail_count,uint8_t sue_CLOCK_CONFIG,uint8_t sue_FLIGHT_PLAN_TYPE) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN]; - _mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE); - _mav_put_int16_t(buf, 4, sue_RCON); - _mav_put_int16_t(buf, 6, sue_TRAP_FLAGS); - _mav_put_int16_t(buf, 8, sue_osc_fail_count); - _mav_put_uint8_t(buf, 10, sue_WIND_ESTIMATION); - _mav_put_uint8_t(buf, 11, sue_GPS_TYPE); - _mav_put_uint8_t(buf, 12, sue_DR); - _mav_put_uint8_t(buf, 13, sue_BOARD_TYPE); - _mav_put_uint8_t(buf, 14, sue_AIRFRAME); - _mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG); - _mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#else - mavlink_serial_udb_extra_f14_t packet; - packet.sue_TRAP_SOURCE = sue_TRAP_SOURCE; - packet.sue_RCON = sue_RCON; - packet.sue_TRAP_FLAGS = sue_TRAP_FLAGS; - packet.sue_osc_fail_count = sue_osc_fail_count; - packet.sue_WIND_ESTIMATION = sue_WIND_ESTIMATION; - packet.sue_GPS_TYPE = sue_GPS_TYPE; - packet.sue_DR = sue_DR; - packet.sue_BOARD_TYPE = sue_BOARD_TYPE; - packet.sue_AIRFRAME = sue_AIRFRAME; - packet.sue_CLOCK_CONFIG = sue_CLOCK_CONFIG; - packet.sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f14 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f14 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f14_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f14_t* serial_udb_extra_f14) -{ - return mavlink_msg_serial_udb_extra_f14_pack(system_id, component_id, msg, serial_udb_extra_f14->sue_WIND_ESTIMATION, serial_udb_extra_f14->sue_GPS_TYPE, serial_udb_extra_f14->sue_DR, serial_udb_extra_f14->sue_BOARD_TYPE, serial_udb_extra_f14->sue_AIRFRAME, serial_udb_extra_f14->sue_RCON, serial_udb_extra_f14->sue_TRAP_FLAGS, serial_udb_extra_f14->sue_TRAP_SOURCE, serial_udb_extra_f14->sue_osc_fail_count, serial_udb_extra_f14->sue_CLOCK_CONFIG, serial_udb_extra_f14->sue_FLIGHT_PLAN_TYPE); -} - -/** - * @brief Encode a serial_udb_extra_f14 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f14 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f14_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f14_t* serial_udb_extra_f14) -{ - return mavlink_msg_serial_udb_extra_f14_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f14->sue_WIND_ESTIMATION, serial_udb_extra_f14->sue_GPS_TYPE, serial_udb_extra_f14->sue_DR, serial_udb_extra_f14->sue_BOARD_TYPE, serial_udb_extra_f14->sue_AIRFRAME, serial_udb_extra_f14->sue_RCON, serial_udb_extra_f14->sue_TRAP_FLAGS, serial_udb_extra_f14->sue_TRAP_SOURCE, serial_udb_extra_f14->sue_osc_fail_count, serial_udb_extra_f14->sue_CLOCK_CONFIG, serial_udb_extra_f14->sue_FLIGHT_PLAN_TYPE); -} - -/** - * @brief Send a serial_udb_extra_f14 message - * @param chan MAVLink channel to send the message - * - * @param sue_WIND_ESTIMATION Serial UDB Extra Wind Estimation Enabled - * @param sue_GPS_TYPE Serial UDB Extra Type of GPS Unit - * @param sue_DR Serial UDB Extra Dead Reckoning Enabled - * @param sue_BOARD_TYPE Serial UDB Extra Type of UDB Hardware - * @param sue_AIRFRAME Serial UDB Extra Type of Airframe - * @param sue_RCON Serial UDB Extra Reboot Regitster of DSPIC - * @param sue_TRAP_FLAGS Serial UDB Extra Last dspic Trap Flags - * @param sue_TRAP_SOURCE Serial UDB Extra Type Program Address of Last Trap - * @param sue_osc_fail_count Serial UDB Extra Number of Ocillator Failures - * @param sue_CLOCK_CONFIG Serial UDB Extra UDB Internal Clock Configuration - * @param sue_FLIGHT_PLAN_TYPE Serial UDB Extra Type of Flight Plan - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f14_send(mavlink_channel_t chan, uint8_t sue_WIND_ESTIMATION, uint8_t sue_GPS_TYPE, uint8_t sue_DR, uint8_t sue_BOARD_TYPE, uint8_t sue_AIRFRAME, int16_t sue_RCON, int16_t sue_TRAP_FLAGS, uint32_t sue_TRAP_SOURCE, int16_t sue_osc_fail_count, uint8_t sue_CLOCK_CONFIG, uint8_t sue_FLIGHT_PLAN_TYPE) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN]; - _mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE); - _mav_put_int16_t(buf, 4, sue_RCON); - _mav_put_int16_t(buf, 6, sue_TRAP_FLAGS); - _mav_put_int16_t(buf, 8, sue_osc_fail_count); - _mav_put_uint8_t(buf, 10, sue_WIND_ESTIMATION); - _mav_put_uint8_t(buf, 11, sue_GPS_TYPE); - _mav_put_uint8_t(buf, 12, sue_DR); - _mav_put_uint8_t(buf, 13, sue_BOARD_TYPE); - _mav_put_uint8_t(buf, 14, sue_AIRFRAME); - _mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG); - _mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#endif -#else - mavlink_serial_udb_extra_f14_t packet; - packet.sue_TRAP_SOURCE = sue_TRAP_SOURCE; - packet.sue_RCON = sue_RCON; - packet.sue_TRAP_FLAGS = sue_TRAP_FLAGS; - packet.sue_osc_fail_count = sue_osc_fail_count; - packet.sue_WIND_ESTIMATION = sue_WIND_ESTIMATION; - packet.sue_GPS_TYPE = sue_GPS_TYPE; - packet.sue_DR = sue_DR; - packet.sue_BOARD_TYPE = sue_BOARD_TYPE; - packet.sue_AIRFRAME = sue_AIRFRAME; - packet.sue_CLOCK_CONFIG = sue_CLOCK_CONFIG; - packet.sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f14_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t sue_WIND_ESTIMATION, uint8_t sue_GPS_TYPE, uint8_t sue_DR, uint8_t sue_BOARD_TYPE, uint8_t sue_AIRFRAME, int16_t sue_RCON, int16_t sue_TRAP_FLAGS, uint32_t sue_TRAP_SOURCE, int16_t sue_osc_fail_count, uint8_t sue_CLOCK_CONFIG, uint8_t sue_FLIGHT_PLAN_TYPE) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, sue_TRAP_SOURCE); - _mav_put_int16_t(buf, 4, sue_RCON); - _mav_put_int16_t(buf, 6, sue_TRAP_FLAGS); - _mav_put_int16_t(buf, 8, sue_osc_fail_count); - _mav_put_uint8_t(buf, 10, sue_WIND_ESTIMATION); - _mav_put_uint8_t(buf, 11, sue_GPS_TYPE); - _mav_put_uint8_t(buf, 12, sue_DR); - _mav_put_uint8_t(buf, 13, sue_BOARD_TYPE); - _mav_put_uint8_t(buf, 14, sue_AIRFRAME); - _mav_put_uint8_t(buf, 15, sue_CLOCK_CONFIG); - _mav_put_uint8_t(buf, 16, sue_FLIGHT_PLAN_TYPE); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#endif -#else - mavlink_serial_udb_extra_f14_t *packet = (mavlink_serial_udb_extra_f14_t *)msgbuf; - packet->sue_TRAP_SOURCE = sue_TRAP_SOURCE; - packet->sue_RCON = sue_RCON; - packet->sue_TRAP_FLAGS = sue_TRAP_FLAGS; - packet->sue_osc_fail_count = sue_osc_fail_count; - packet->sue_WIND_ESTIMATION = sue_WIND_ESTIMATION; - packet->sue_GPS_TYPE = sue_GPS_TYPE; - packet->sue_DR = sue_DR; - packet->sue_BOARD_TYPE = sue_BOARD_TYPE; - packet->sue_AIRFRAME = sue_AIRFRAME; - packet->sue_CLOCK_CONFIG = sue_CLOCK_CONFIG; - packet->sue_FLIGHT_PLAN_TYPE = sue_FLIGHT_PLAN_TYPE; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F14 UNPACKING - - -/** - * @brief Get field sue_WIND_ESTIMATION from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Wind Estimation Enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_WIND_ESTIMATION(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field sue_GPS_TYPE from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Type of GPS Unit - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_GPS_TYPE(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field sue_DR from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Dead Reckoning Enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_DR(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 12); -} - -/** - * @brief Get field sue_BOARD_TYPE from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Type of UDB Hardware - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_BOARD_TYPE(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 13); -} - -/** - * @brief Get field sue_AIRFRAME from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Type of Airframe - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_AIRFRAME(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Get field sue_RCON from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Reboot Regitster of DSPIC - */ -static inline int16_t mavlink_msg_serial_udb_extra_f14_get_sue_RCON(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 4); -} - -/** - * @brief Get field sue_TRAP_FLAGS from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Last dspic Trap Flags - */ -static inline int16_t mavlink_msg_serial_udb_extra_f14_get_sue_TRAP_FLAGS(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 6); -} - -/** - * @brief Get field sue_TRAP_SOURCE from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Type Program Address of Last Trap - */ -static inline uint32_t mavlink_msg_serial_udb_extra_f14_get_sue_TRAP_SOURCE(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field sue_osc_fail_count from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Number of Ocillator Failures - */ -static inline int16_t mavlink_msg_serial_udb_extra_f14_get_sue_osc_fail_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field sue_CLOCK_CONFIG from serial_udb_extra_f14 message - * - * @return Serial UDB Extra UDB Internal Clock Configuration - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_CLOCK_CONFIG(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 15); -} - -/** - * @brief Get field sue_FLIGHT_PLAN_TYPE from serial_udb_extra_f14 message - * - * @return Serial UDB Extra Type of Flight Plan - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f14_get_sue_FLIGHT_PLAN_TYPE(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Decode a serial_udb_extra_f14 message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f14 C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f14_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f14_t* serial_udb_extra_f14) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_udb_extra_f14->sue_TRAP_SOURCE = mavlink_msg_serial_udb_extra_f14_get_sue_TRAP_SOURCE(msg); - serial_udb_extra_f14->sue_RCON = mavlink_msg_serial_udb_extra_f14_get_sue_RCON(msg); - serial_udb_extra_f14->sue_TRAP_FLAGS = mavlink_msg_serial_udb_extra_f14_get_sue_TRAP_FLAGS(msg); - serial_udb_extra_f14->sue_osc_fail_count = mavlink_msg_serial_udb_extra_f14_get_sue_osc_fail_count(msg); - serial_udb_extra_f14->sue_WIND_ESTIMATION = mavlink_msg_serial_udb_extra_f14_get_sue_WIND_ESTIMATION(msg); - serial_udb_extra_f14->sue_GPS_TYPE = mavlink_msg_serial_udb_extra_f14_get_sue_GPS_TYPE(msg); - serial_udb_extra_f14->sue_DR = mavlink_msg_serial_udb_extra_f14_get_sue_DR(msg); - serial_udb_extra_f14->sue_BOARD_TYPE = mavlink_msg_serial_udb_extra_f14_get_sue_BOARD_TYPE(msg); - serial_udb_extra_f14->sue_AIRFRAME = mavlink_msg_serial_udb_extra_f14_get_sue_AIRFRAME(msg); - serial_udb_extra_f14->sue_CLOCK_CONFIG = mavlink_msg_serial_udb_extra_f14_get_sue_CLOCK_CONFIG(msg); - serial_udb_extra_f14->sue_FLIGHT_PLAN_TYPE = mavlink_msg_serial_udb_extra_f14_get_sue_FLIGHT_PLAN_TYPE(msg); -#else - memcpy(serial_udb_extra_f14, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F14_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h deleted file mode 100644 index 77666407d..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f15.h +++ /dev/null @@ -1,234 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F15 PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15 179 - -typedef struct __mavlink_serial_udb_extra_f15_t -{ - uint8_t sue_ID_VEHICLE_MODEL_NAME[40]; ///< Serial UDB Extra Model Name Of Vehicle - uint8_t sue_ID_VEHICLE_REGISTRATION[20]; ///< Serial UDB Extra Registraton Number of Vehicle -} mavlink_serial_udb_extra_f15_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN 60 -#define MAVLINK_MSG_ID_179_LEN 60 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC 7 -#define MAVLINK_MSG_ID_179_CRC 7 - -#define MAVLINK_MSG_SERIAL_UDB_EXTRA_F15_FIELD_SUE_ID_VEHICLE_MODEL_NAME_LEN 40 -#define MAVLINK_MSG_SERIAL_UDB_EXTRA_F15_FIELD_SUE_ID_VEHICLE_REGISTRATION_LEN 20 - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F15 { \ - "SERIAL_UDB_EXTRA_F15", \ - 2, \ - { { "sue_ID_VEHICLE_MODEL_NAME", NULL, MAVLINK_TYPE_UINT8_T, 40, 0, offsetof(mavlink_serial_udb_extra_f15_t, sue_ID_VEHICLE_MODEL_NAME) }, \ - { "sue_ID_VEHICLE_REGISTRATION", NULL, MAVLINK_TYPE_UINT8_T, 20, 40, offsetof(mavlink_serial_udb_extra_f15_t, sue_ID_VEHICLE_REGISTRATION) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f15 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_ID_VEHICLE_MODEL_NAME Serial UDB Extra Model Name Of Vehicle - * @param sue_ID_VEHICLE_REGISTRATION Serial UDB Extra Registraton Number of Vehicle - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f15_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const uint8_t *sue_ID_VEHICLE_MODEL_NAME, const uint8_t *sue_ID_VEHICLE_REGISTRATION) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN]; - - _mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40); - _mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#else - mavlink_serial_udb_extra_f15_t packet; - - mav_array_memcpy(packet.sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40); - mav_array_memcpy(packet.sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f15 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_ID_VEHICLE_MODEL_NAME Serial UDB Extra Model Name Of Vehicle - * @param sue_ID_VEHICLE_REGISTRATION Serial UDB Extra Registraton Number of Vehicle - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f15_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const uint8_t *sue_ID_VEHICLE_MODEL_NAME,const uint8_t *sue_ID_VEHICLE_REGISTRATION) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN]; - - _mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40); - _mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#else - mavlink_serial_udb_extra_f15_t packet; - - mav_array_memcpy(packet.sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40); - mav_array_memcpy(packet.sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f15 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f15 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f15_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f15_t* serial_udb_extra_f15) -{ - return mavlink_msg_serial_udb_extra_f15_pack(system_id, component_id, msg, serial_udb_extra_f15->sue_ID_VEHICLE_MODEL_NAME, serial_udb_extra_f15->sue_ID_VEHICLE_REGISTRATION); -} - -/** - * @brief Encode a serial_udb_extra_f15 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f15 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f15_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f15_t* serial_udb_extra_f15) -{ - return mavlink_msg_serial_udb_extra_f15_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f15->sue_ID_VEHICLE_MODEL_NAME, serial_udb_extra_f15->sue_ID_VEHICLE_REGISTRATION); -} - -/** - * @brief Send a serial_udb_extra_f15 message - * @param chan MAVLink channel to send the message - * - * @param sue_ID_VEHICLE_MODEL_NAME Serial UDB Extra Model Name Of Vehicle - * @param sue_ID_VEHICLE_REGISTRATION Serial UDB Extra Registraton Number of Vehicle - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f15_send(mavlink_channel_t chan, const uint8_t *sue_ID_VEHICLE_MODEL_NAME, const uint8_t *sue_ID_VEHICLE_REGISTRATION) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN]; - - _mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40); - _mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#endif -#else - mavlink_serial_udb_extra_f15_t packet; - - mav_array_memcpy(packet.sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40); - mav_array_memcpy(packet.sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f15_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *sue_ID_VEHICLE_MODEL_NAME, const uint8_t *sue_ID_VEHICLE_REGISTRATION) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_uint8_t_array(buf, 0, sue_ID_VEHICLE_MODEL_NAME, 40); - _mav_put_uint8_t_array(buf, 40, sue_ID_VEHICLE_REGISTRATION, 20); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#endif -#else - mavlink_serial_udb_extra_f15_t *packet = (mavlink_serial_udb_extra_f15_t *)msgbuf; - - mav_array_memcpy(packet->sue_ID_VEHICLE_MODEL_NAME, sue_ID_VEHICLE_MODEL_NAME, sizeof(uint8_t)*40); - mav_array_memcpy(packet->sue_ID_VEHICLE_REGISTRATION, sue_ID_VEHICLE_REGISTRATION, sizeof(uint8_t)*20); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F15 UNPACKING - - -/** - * @brief Get field sue_ID_VEHICLE_MODEL_NAME from serial_udb_extra_f15 message - * - * @return Serial UDB Extra Model Name Of Vehicle - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_MODEL_NAME(const mavlink_message_t* msg, uint8_t *sue_ID_VEHICLE_MODEL_NAME) -{ - return _MAV_RETURN_uint8_t_array(msg, sue_ID_VEHICLE_MODEL_NAME, 40, 0); -} - -/** - * @brief Get field sue_ID_VEHICLE_REGISTRATION from serial_udb_extra_f15 message - * - * @return Serial UDB Extra Registraton Number of Vehicle - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_REGISTRATION(const mavlink_message_t* msg, uint8_t *sue_ID_VEHICLE_REGISTRATION) -{ - return _MAV_RETURN_uint8_t_array(msg, sue_ID_VEHICLE_REGISTRATION, 20, 40); -} - -/** - * @brief Decode a serial_udb_extra_f15 message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f15 C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f15_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f15_t* serial_udb_extra_f15) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_MODEL_NAME(msg, serial_udb_extra_f15->sue_ID_VEHICLE_MODEL_NAME); - mavlink_msg_serial_udb_extra_f15_get_sue_ID_VEHICLE_REGISTRATION(msg, serial_udb_extra_f15->sue_ID_VEHICLE_REGISTRATION); -#else - memcpy(serial_udb_extra_f15, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F15_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h deleted file mode 100644 index ca9f0556f..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f16.h +++ /dev/null @@ -1,234 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F16 PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16 180 - -typedef struct __mavlink_serial_udb_extra_f16_t -{ - uint8_t sue_ID_LEAD_PILOT[40]; ///< Serial UDB Extra Name of Expected Lead Pilot - uint8_t sue_ID_DIY_DRONES_URL[70]; ///< Serial UDB Extra URL of Lead Pilot or Team -} mavlink_serial_udb_extra_f16_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN 110 -#define MAVLINK_MSG_ID_180_LEN 110 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC 222 -#define MAVLINK_MSG_ID_180_CRC 222 - -#define MAVLINK_MSG_SERIAL_UDB_EXTRA_F16_FIELD_SUE_ID_LEAD_PILOT_LEN 40 -#define MAVLINK_MSG_SERIAL_UDB_EXTRA_F16_FIELD_SUE_ID_DIY_DRONES_URL_LEN 70 - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F16 { \ - "SERIAL_UDB_EXTRA_F16", \ - 2, \ - { { "sue_ID_LEAD_PILOT", NULL, MAVLINK_TYPE_UINT8_T, 40, 0, offsetof(mavlink_serial_udb_extra_f16_t, sue_ID_LEAD_PILOT) }, \ - { "sue_ID_DIY_DRONES_URL", NULL, MAVLINK_TYPE_UINT8_T, 70, 40, offsetof(mavlink_serial_udb_extra_f16_t, sue_ID_DIY_DRONES_URL) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f16 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_ID_LEAD_PILOT Serial UDB Extra Name of Expected Lead Pilot - * @param sue_ID_DIY_DRONES_URL Serial UDB Extra URL of Lead Pilot or Team - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f16_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const uint8_t *sue_ID_LEAD_PILOT, const uint8_t *sue_ID_DIY_DRONES_URL) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN]; - - _mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40); - _mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#else - mavlink_serial_udb_extra_f16_t packet; - - mav_array_memcpy(packet.sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40); - mav_array_memcpy(packet.sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f16 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_ID_LEAD_PILOT Serial UDB Extra Name of Expected Lead Pilot - * @param sue_ID_DIY_DRONES_URL Serial UDB Extra URL of Lead Pilot or Team - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f16_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const uint8_t *sue_ID_LEAD_PILOT,const uint8_t *sue_ID_DIY_DRONES_URL) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN]; - - _mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40); - _mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#else - mavlink_serial_udb_extra_f16_t packet; - - mav_array_memcpy(packet.sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40); - mav_array_memcpy(packet.sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f16 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f16 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f16_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f16_t* serial_udb_extra_f16) -{ - return mavlink_msg_serial_udb_extra_f16_pack(system_id, component_id, msg, serial_udb_extra_f16->sue_ID_LEAD_PILOT, serial_udb_extra_f16->sue_ID_DIY_DRONES_URL); -} - -/** - * @brief Encode a serial_udb_extra_f16 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f16 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f16_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f16_t* serial_udb_extra_f16) -{ - return mavlink_msg_serial_udb_extra_f16_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f16->sue_ID_LEAD_PILOT, serial_udb_extra_f16->sue_ID_DIY_DRONES_URL); -} - -/** - * @brief Send a serial_udb_extra_f16 message - * @param chan MAVLink channel to send the message - * - * @param sue_ID_LEAD_PILOT Serial UDB Extra Name of Expected Lead Pilot - * @param sue_ID_DIY_DRONES_URL Serial UDB Extra URL of Lead Pilot or Team - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f16_send(mavlink_channel_t chan, const uint8_t *sue_ID_LEAD_PILOT, const uint8_t *sue_ID_DIY_DRONES_URL) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN]; - - _mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40); - _mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#endif -#else - mavlink_serial_udb_extra_f16_t packet; - - mav_array_memcpy(packet.sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40); - mav_array_memcpy(packet.sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f16_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *sue_ID_LEAD_PILOT, const uint8_t *sue_ID_DIY_DRONES_URL) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_uint8_t_array(buf, 0, sue_ID_LEAD_PILOT, 40); - _mav_put_uint8_t_array(buf, 40, sue_ID_DIY_DRONES_URL, 70); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#endif -#else - mavlink_serial_udb_extra_f16_t *packet = (mavlink_serial_udb_extra_f16_t *)msgbuf; - - mav_array_memcpy(packet->sue_ID_LEAD_PILOT, sue_ID_LEAD_PILOT, sizeof(uint8_t)*40); - mav_array_memcpy(packet->sue_ID_DIY_DRONES_URL, sue_ID_DIY_DRONES_URL, sizeof(uint8_t)*70); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F16 UNPACKING - - -/** - * @brief Get field sue_ID_LEAD_PILOT from serial_udb_extra_f16 message - * - * @return Serial UDB Extra Name of Expected Lead Pilot - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f16_get_sue_ID_LEAD_PILOT(const mavlink_message_t* msg, uint8_t *sue_ID_LEAD_PILOT) -{ - return _MAV_RETURN_uint8_t_array(msg, sue_ID_LEAD_PILOT, 40, 0); -} - -/** - * @brief Get field sue_ID_DIY_DRONES_URL from serial_udb_extra_f16 message - * - * @return Serial UDB Extra URL of Lead Pilot or Team - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f16_get_sue_ID_DIY_DRONES_URL(const mavlink_message_t* msg, uint8_t *sue_ID_DIY_DRONES_URL) -{ - return _MAV_RETURN_uint8_t_array(msg, sue_ID_DIY_DRONES_URL, 70, 40); -} - -/** - * @brief Decode a serial_udb_extra_f16 message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f16 C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f16_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f16_t* serial_udb_extra_f16) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_serial_udb_extra_f16_get_sue_ID_LEAD_PILOT(msg, serial_udb_extra_f16->sue_ID_LEAD_PILOT); - mavlink_msg_serial_udb_extra_f16_get_sue_ID_DIY_DRONES_URL(msg, serial_udb_extra_f16->sue_ID_DIY_DRONES_URL); -#else - memcpy(serial_udb_extra_f16, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F16_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h deleted file mode 100644 index 41b9f09c0..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_a.h +++ /dev/null @@ -1,857 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F2_A PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A 170 - -typedef struct __mavlink_serial_udb_extra_f2_a_t -{ - uint32_t sue_time; ///< Serial UDB Extra Time - int32_t sue_latitude; ///< Serial UDB Extra Latitude - int32_t sue_longitude; ///< Serial UDB Extra Longitude - int32_t sue_altitude; ///< Serial UDB Extra Altitude - uint16_t sue_waypoint_index; ///< Serial UDB Extra Waypoint Index - int16_t sue_rmat0; ///< Serial UDB Extra Rmat 0 - int16_t sue_rmat1; ///< Serial UDB Extra Rmat 1 - int16_t sue_rmat2; ///< Serial UDB Extra Rmat 2 - int16_t sue_rmat3; ///< Serial UDB Extra Rmat 3 - int16_t sue_rmat4; ///< Serial UDB Extra Rmat 4 - int16_t sue_rmat5; ///< Serial UDB Extra Rmat 5 - int16_t sue_rmat6; ///< Serial UDB Extra Rmat 6 - int16_t sue_rmat7; ///< Serial UDB Extra Rmat 7 - int16_t sue_rmat8; ///< Serial UDB Extra Rmat 8 - uint16_t sue_cog; ///< Serial UDB Extra GPS Course Over Ground - int16_t sue_sog; ///< Serial UDB Extra Speed Over Ground - uint16_t sue_cpu_load; ///< Serial UDB Extra CPU Load - int16_t sue_voltage_milis; ///< Serial UDB Extra Voltage in MilliVolts - uint16_t sue_air_speed_3DIMU; ///< Serial UDB Extra 3D IMU Air Speed - int16_t sue_estimated_wind_0; ///< Serial UDB Extra Estimated Wind 0 - int16_t sue_estimated_wind_1; ///< Serial UDB Extra Estimated Wind 1 - int16_t sue_estimated_wind_2; ///< Serial UDB Extra Estimated Wind 2 - int16_t sue_magFieldEarth0; ///< Serial UDB Extra Magnetic Field Earth 0 - int16_t sue_magFieldEarth1; ///< Serial UDB Extra Magnetic Field Earth 1 - int16_t sue_magFieldEarth2; ///< Serial UDB Extra Magnetic Field Earth 2 - int16_t sue_svs; ///< Serial UDB Extra Number of Sattelites in View - int16_t sue_hdop; ///< Serial UDB Extra GPS Horizontal Dilution of Precision - uint8_t sue_status; ///< Serial UDB Extra Status -} mavlink_serial_udb_extra_f2_a_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN 63 -#define MAVLINK_MSG_ID_170_LEN 63 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC 150 -#define MAVLINK_MSG_ID_170_CRC 150 - - - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F2_A { \ - "SERIAL_UDB_EXTRA_F2_A", \ - 28, \ - { { "sue_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_time) }, \ - { "sue_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_latitude) }, \ - { "sue_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_longitude) }, \ - { "sue_altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_altitude) }, \ - { "sue_waypoint_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_waypoint_index) }, \ - { "sue_rmat0", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat0) }, \ - { "sue_rmat1", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat1) }, \ - { "sue_rmat2", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat2) }, \ - { "sue_rmat3", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat3) }, \ - { "sue_rmat4", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat4) }, \ - { "sue_rmat5", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat5) }, \ - { "sue_rmat6", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat6) }, \ - { "sue_rmat7", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat7) }, \ - { "sue_rmat8", NULL, MAVLINK_TYPE_INT16_T, 0, 34, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_rmat8) }, \ - { "sue_cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_cog) }, \ - { "sue_sog", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_sog) }, \ - { "sue_cpu_load", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_cpu_load) }, \ - { "sue_voltage_milis", NULL, MAVLINK_TYPE_INT16_T, 0, 42, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_voltage_milis) }, \ - { "sue_air_speed_3DIMU", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_air_speed_3DIMU) }, \ - { "sue_estimated_wind_0", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_estimated_wind_0) }, \ - { "sue_estimated_wind_1", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_estimated_wind_1) }, \ - { "sue_estimated_wind_2", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_estimated_wind_2) }, \ - { "sue_magFieldEarth0", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_magFieldEarth0) }, \ - { "sue_magFieldEarth1", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_magFieldEarth1) }, \ - { "sue_magFieldEarth2", NULL, MAVLINK_TYPE_INT16_T, 0, 56, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_magFieldEarth2) }, \ - { "sue_svs", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_svs) }, \ - { "sue_hdop", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_hdop) }, \ - { "sue_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_serial_udb_extra_f2_a_t, sue_status) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f2_a message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_time Serial UDB Extra Time - * @param sue_status Serial UDB Extra Status - * @param sue_latitude Serial UDB Extra Latitude - * @param sue_longitude Serial UDB Extra Longitude - * @param sue_altitude Serial UDB Extra Altitude - * @param sue_waypoint_index Serial UDB Extra Waypoint Index - * @param sue_rmat0 Serial UDB Extra Rmat 0 - * @param sue_rmat1 Serial UDB Extra Rmat 1 - * @param sue_rmat2 Serial UDB Extra Rmat 2 - * @param sue_rmat3 Serial UDB Extra Rmat 3 - * @param sue_rmat4 Serial UDB Extra Rmat 4 - * @param sue_rmat5 Serial UDB Extra Rmat 5 - * @param sue_rmat6 Serial UDB Extra Rmat 6 - * @param sue_rmat7 Serial UDB Extra Rmat 7 - * @param sue_rmat8 Serial UDB Extra Rmat 8 - * @param sue_cog Serial UDB Extra GPS Course Over Ground - * @param sue_sog Serial UDB Extra Speed Over Ground - * @param sue_cpu_load Serial UDB Extra CPU Load - * @param sue_voltage_milis Serial UDB Extra Voltage in MilliVolts - * @param sue_air_speed_3DIMU Serial UDB Extra 3D IMU Air Speed - * @param sue_estimated_wind_0 Serial UDB Extra Estimated Wind 0 - * @param sue_estimated_wind_1 Serial UDB Extra Estimated Wind 1 - * @param sue_estimated_wind_2 Serial UDB Extra Estimated Wind 2 - * @param sue_magFieldEarth0 Serial UDB Extra Magnetic Field Earth 0 - * @param sue_magFieldEarth1 Serial UDB Extra Magnetic Field Earth 1 - * @param sue_magFieldEarth2 Serial UDB Extra Magnetic Field Earth 2 - * @param sue_svs Serial UDB Extra Number of Sattelites in View - * @param sue_hdop Serial UDB Extra GPS Horizontal Dilution of Precision - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t sue_time, uint8_t sue_status, int32_t sue_latitude, int32_t sue_longitude, int32_t sue_altitude, uint16_t sue_waypoint_index, int16_t sue_rmat0, int16_t sue_rmat1, int16_t sue_rmat2, int16_t sue_rmat3, int16_t sue_rmat4, int16_t sue_rmat5, int16_t sue_rmat6, int16_t sue_rmat7, int16_t sue_rmat8, uint16_t sue_cog, int16_t sue_sog, uint16_t sue_cpu_load, int16_t sue_voltage_milis, uint16_t sue_air_speed_3DIMU, int16_t sue_estimated_wind_0, int16_t sue_estimated_wind_1, int16_t sue_estimated_wind_2, int16_t sue_magFieldEarth0, int16_t sue_magFieldEarth1, int16_t sue_magFieldEarth2, int16_t sue_svs, int16_t sue_hdop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN]; - _mav_put_uint32_t(buf, 0, sue_time); - _mav_put_int32_t(buf, 4, sue_latitude); - _mav_put_int32_t(buf, 8, sue_longitude); - _mav_put_int32_t(buf, 12, sue_altitude); - _mav_put_uint16_t(buf, 16, sue_waypoint_index); - _mav_put_int16_t(buf, 18, sue_rmat0); - _mav_put_int16_t(buf, 20, sue_rmat1); - _mav_put_int16_t(buf, 22, sue_rmat2); - _mav_put_int16_t(buf, 24, sue_rmat3); - _mav_put_int16_t(buf, 26, sue_rmat4); - _mav_put_int16_t(buf, 28, sue_rmat5); - _mav_put_int16_t(buf, 30, sue_rmat6); - _mav_put_int16_t(buf, 32, sue_rmat7); - _mav_put_int16_t(buf, 34, sue_rmat8); - _mav_put_uint16_t(buf, 36, sue_cog); - _mav_put_int16_t(buf, 38, sue_sog); - _mav_put_uint16_t(buf, 40, sue_cpu_load); - _mav_put_int16_t(buf, 42, sue_voltage_milis); - _mav_put_uint16_t(buf, 44, sue_air_speed_3DIMU); - _mav_put_int16_t(buf, 46, sue_estimated_wind_0); - _mav_put_int16_t(buf, 48, sue_estimated_wind_1); - _mav_put_int16_t(buf, 50, sue_estimated_wind_2); - _mav_put_int16_t(buf, 52, sue_magFieldEarth0); - _mav_put_int16_t(buf, 54, sue_magFieldEarth1); - _mav_put_int16_t(buf, 56, sue_magFieldEarth2); - _mav_put_int16_t(buf, 58, sue_svs); - _mav_put_int16_t(buf, 60, sue_hdop); - _mav_put_uint8_t(buf, 62, sue_status); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#else - mavlink_serial_udb_extra_f2_a_t packet; - packet.sue_time = sue_time; - packet.sue_latitude = sue_latitude; - packet.sue_longitude = sue_longitude; - packet.sue_altitude = sue_altitude; - packet.sue_waypoint_index = sue_waypoint_index; - packet.sue_rmat0 = sue_rmat0; - packet.sue_rmat1 = sue_rmat1; - packet.sue_rmat2 = sue_rmat2; - packet.sue_rmat3 = sue_rmat3; - packet.sue_rmat4 = sue_rmat4; - packet.sue_rmat5 = sue_rmat5; - packet.sue_rmat6 = sue_rmat6; - packet.sue_rmat7 = sue_rmat7; - packet.sue_rmat8 = sue_rmat8; - packet.sue_cog = sue_cog; - packet.sue_sog = sue_sog; - packet.sue_cpu_load = sue_cpu_load; - packet.sue_voltage_milis = sue_voltage_milis; - packet.sue_air_speed_3DIMU = sue_air_speed_3DIMU; - packet.sue_estimated_wind_0 = sue_estimated_wind_0; - packet.sue_estimated_wind_1 = sue_estimated_wind_1; - packet.sue_estimated_wind_2 = sue_estimated_wind_2; - packet.sue_magFieldEarth0 = sue_magFieldEarth0; - packet.sue_magFieldEarth1 = sue_magFieldEarth1; - packet.sue_magFieldEarth2 = sue_magFieldEarth2; - packet.sue_svs = sue_svs; - packet.sue_hdop = sue_hdop; - packet.sue_status = sue_status; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f2_a message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_time Serial UDB Extra Time - * @param sue_status Serial UDB Extra Status - * @param sue_latitude Serial UDB Extra Latitude - * @param sue_longitude Serial UDB Extra Longitude - * @param sue_altitude Serial UDB Extra Altitude - * @param sue_waypoint_index Serial UDB Extra Waypoint Index - * @param sue_rmat0 Serial UDB Extra Rmat 0 - * @param sue_rmat1 Serial UDB Extra Rmat 1 - * @param sue_rmat2 Serial UDB Extra Rmat 2 - * @param sue_rmat3 Serial UDB Extra Rmat 3 - * @param sue_rmat4 Serial UDB Extra Rmat 4 - * @param sue_rmat5 Serial UDB Extra Rmat 5 - * @param sue_rmat6 Serial UDB Extra Rmat 6 - * @param sue_rmat7 Serial UDB Extra Rmat 7 - * @param sue_rmat8 Serial UDB Extra Rmat 8 - * @param sue_cog Serial UDB Extra GPS Course Over Ground - * @param sue_sog Serial UDB Extra Speed Over Ground - * @param sue_cpu_load Serial UDB Extra CPU Load - * @param sue_voltage_milis Serial UDB Extra Voltage in MilliVolts - * @param sue_air_speed_3DIMU Serial UDB Extra 3D IMU Air Speed - * @param sue_estimated_wind_0 Serial UDB Extra Estimated Wind 0 - * @param sue_estimated_wind_1 Serial UDB Extra Estimated Wind 1 - * @param sue_estimated_wind_2 Serial UDB Extra Estimated Wind 2 - * @param sue_magFieldEarth0 Serial UDB Extra Magnetic Field Earth 0 - * @param sue_magFieldEarth1 Serial UDB Extra Magnetic Field Earth 1 - * @param sue_magFieldEarth2 Serial UDB Extra Magnetic Field Earth 2 - * @param sue_svs Serial UDB Extra Number of Sattelites in View - * @param sue_hdop Serial UDB Extra GPS Horizontal Dilution of Precision - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t sue_time,uint8_t sue_status,int32_t sue_latitude,int32_t sue_longitude,int32_t sue_altitude,uint16_t sue_waypoint_index,int16_t sue_rmat0,int16_t sue_rmat1,int16_t sue_rmat2,int16_t sue_rmat3,int16_t sue_rmat4,int16_t sue_rmat5,int16_t sue_rmat6,int16_t sue_rmat7,int16_t sue_rmat8,uint16_t sue_cog,int16_t sue_sog,uint16_t sue_cpu_load,int16_t sue_voltage_milis,uint16_t sue_air_speed_3DIMU,int16_t sue_estimated_wind_0,int16_t sue_estimated_wind_1,int16_t sue_estimated_wind_2,int16_t sue_magFieldEarth0,int16_t sue_magFieldEarth1,int16_t sue_magFieldEarth2,int16_t sue_svs,int16_t sue_hdop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN]; - _mav_put_uint32_t(buf, 0, sue_time); - _mav_put_int32_t(buf, 4, sue_latitude); - _mav_put_int32_t(buf, 8, sue_longitude); - _mav_put_int32_t(buf, 12, sue_altitude); - _mav_put_uint16_t(buf, 16, sue_waypoint_index); - _mav_put_int16_t(buf, 18, sue_rmat0); - _mav_put_int16_t(buf, 20, sue_rmat1); - _mav_put_int16_t(buf, 22, sue_rmat2); - _mav_put_int16_t(buf, 24, sue_rmat3); - _mav_put_int16_t(buf, 26, sue_rmat4); - _mav_put_int16_t(buf, 28, sue_rmat5); - _mav_put_int16_t(buf, 30, sue_rmat6); - _mav_put_int16_t(buf, 32, sue_rmat7); - _mav_put_int16_t(buf, 34, sue_rmat8); - _mav_put_uint16_t(buf, 36, sue_cog); - _mav_put_int16_t(buf, 38, sue_sog); - _mav_put_uint16_t(buf, 40, sue_cpu_load); - _mav_put_int16_t(buf, 42, sue_voltage_milis); - _mav_put_uint16_t(buf, 44, sue_air_speed_3DIMU); - _mav_put_int16_t(buf, 46, sue_estimated_wind_0); - _mav_put_int16_t(buf, 48, sue_estimated_wind_1); - _mav_put_int16_t(buf, 50, sue_estimated_wind_2); - _mav_put_int16_t(buf, 52, sue_magFieldEarth0); - _mav_put_int16_t(buf, 54, sue_magFieldEarth1); - _mav_put_int16_t(buf, 56, sue_magFieldEarth2); - _mav_put_int16_t(buf, 58, sue_svs); - _mav_put_int16_t(buf, 60, sue_hdop); - _mav_put_uint8_t(buf, 62, sue_status); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#else - mavlink_serial_udb_extra_f2_a_t packet; - packet.sue_time = sue_time; - packet.sue_latitude = sue_latitude; - packet.sue_longitude = sue_longitude; - packet.sue_altitude = sue_altitude; - packet.sue_waypoint_index = sue_waypoint_index; - packet.sue_rmat0 = sue_rmat0; - packet.sue_rmat1 = sue_rmat1; - packet.sue_rmat2 = sue_rmat2; - packet.sue_rmat3 = sue_rmat3; - packet.sue_rmat4 = sue_rmat4; - packet.sue_rmat5 = sue_rmat5; - packet.sue_rmat6 = sue_rmat6; - packet.sue_rmat7 = sue_rmat7; - packet.sue_rmat8 = sue_rmat8; - packet.sue_cog = sue_cog; - packet.sue_sog = sue_sog; - packet.sue_cpu_load = sue_cpu_load; - packet.sue_voltage_milis = sue_voltage_milis; - packet.sue_air_speed_3DIMU = sue_air_speed_3DIMU; - packet.sue_estimated_wind_0 = sue_estimated_wind_0; - packet.sue_estimated_wind_1 = sue_estimated_wind_1; - packet.sue_estimated_wind_2 = sue_estimated_wind_2; - packet.sue_magFieldEarth0 = sue_magFieldEarth0; - packet.sue_magFieldEarth1 = sue_magFieldEarth1; - packet.sue_magFieldEarth2 = sue_magFieldEarth2; - packet.sue_svs = sue_svs; - packet.sue_hdop = sue_hdop; - packet.sue_status = sue_status; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f2_a struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f2_a C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f2_a_t* serial_udb_extra_f2_a) -{ - return mavlink_msg_serial_udb_extra_f2_a_pack(system_id, component_id, msg, serial_udb_extra_f2_a->sue_time, serial_udb_extra_f2_a->sue_status, serial_udb_extra_f2_a->sue_latitude, serial_udb_extra_f2_a->sue_longitude, serial_udb_extra_f2_a->sue_altitude, serial_udb_extra_f2_a->sue_waypoint_index, serial_udb_extra_f2_a->sue_rmat0, serial_udb_extra_f2_a->sue_rmat1, serial_udb_extra_f2_a->sue_rmat2, serial_udb_extra_f2_a->sue_rmat3, serial_udb_extra_f2_a->sue_rmat4, serial_udb_extra_f2_a->sue_rmat5, serial_udb_extra_f2_a->sue_rmat6, serial_udb_extra_f2_a->sue_rmat7, serial_udb_extra_f2_a->sue_rmat8, serial_udb_extra_f2_a->sue_cog, serial_udb_extra_f2_a->sue_sog, serial_udb_extra_f2_a->sue_cpu_load, serial_udb_extra_f2_a->sue_voltage_milis, serial_udb_extra_f2_a->sue_air_speed_3DIMU, serial_udb_extra_f2_a->sue_estimated_wind_0, serial_udb_extra_f2_a->sue_estimated_wind_1, serial_udb_extra_f2_a->sue_estimated_wind_2, serial_udb_extra_f2_a->sue_magFieldEarth0, serial_udb_extra_f2_a->sue_magFieldEarth1, serial_udb_extra_f2_a->sue_magFieldEarth2, serial_udb_extra_f2_a->sue_svs, serial_udb_extra_f2_a->sue_hdop); -} - -/** - * @brief Encode a serial_udb_extra_f2_a struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f2_a C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f2_a_t* serial_udb_extra_f2_a) -{ - return mavlink_msg_serial_udb_extra_f2_a_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f2_a->sue_time, serial_udb_extra_f2_a->sue_status, serial_udb_extra_f2_a->sue_latitude, serial_udb_extra_f2_a->sue_longitude, serial_udb_extra_f2_a->sue_altitude, serial_udb_extra_f2_a->sue_waypoint_index, serial_udb_extra_f2_a->sue_rmat0, serial_udb_extra_f2_a->sue_rmat1, serial_udb_extra_f2_a->sue_rmat2, serial_udb_extra_f2_a->sue_rmat3, serial_udb_extra_f2_a->sue_rmat4, serial_udb_extra_f2_a->sue_rmat5, serial_udb_extra_f2_a->sue_rmat6, serial_udb_extra_f2_a->sue_rmat7, serial_udb_extra_f2_a->sue_rmat8, serial_udb_extra_f2_a->sue_cog, serial_udb_extra_f2_a->sue_sog, serial_udb_extra_f2_a->sue_cpu_load, serial_udb_extra_f2_a->sue_voltage_milis, serial_udb_extra_f2_a->sue_air_speed_3DIMU, serial_udb_extra_f2_a->sue_estimated_wind_0, serial_udb_extra_f2_a->sue_estimated_wind_1, serial_udb_extra_f2_a->sue_estimated_wind_2, serial_udb_extra_f2_a->sue_magFieldEarth0, serial_udb_extra_f2_a->sue_magFieldEarth1, serial_udb_extra_f2_a->sue_magFieldEarth2, serial_udb_extra_f2_a->sue_svs, serial_udb_extra_f2_a->sue_hdop); -} - -/** - * @brief Send a serial_udb_extra_f2_a message - * @param chan MAVLink channel to send the message - * - * @param sue_time Serial UDB Extra Time - * @param sue_status Serial UDB Extra Status - * @param sue_latitude Serial UDB Extra Latitude - * @param sue_longitude Serial UDB Extra Longitude - * @param sue_altitude Serial UDB Extra Altitude - * @param sue_waypoint_index Serial UDB Extra Waypoint Index - * @param sue_rmat0 Serial UDB Extra Rmat 0 - * @param sue_rmat1 Serial UDB Extra Rmat 1 - * @param sue_rmat2 Serial UDB Extra Rmat 2 - * @param sue_rmat3 Serial UDB Extra Rmat 3 - * @param sue_rmat4 Serial UDB Extra Rmat 4 - * @param sue_rmat5 Serial UDB Extra Rmat 5 - * @param sue_rmat6 Serial UDB Extra Rmat 6 - * @param sue_rmat7 Serial UDB Extra Rmat 7 - * @param sue_rmat8 Serial UDB Extra Rmat 8 - * @param sue_cog Serial UDB Extra GPS Course Over Ground - * @param sue_sog Serial UDB Extra Speed Over Ground - * @param sue_cpu_load Serial UDB Extra CPU Load - * @param sue_voltage_milis Serial UDB Extra Voltage in MilliVolts - * @param sue_air_speed_3DIMU Serial UDB Extra 3D IMU Air Speed - * @param sue_estimated_wind_0 Serial UDB Extra Estimated Wind 0 - * @param sue_estimated_wind_1 Serial UDB Extra Estimated Wind 1 - * @param sue_estimated_wind_2 Serial UDB Extra Estimated Wind 2 - * @param sue_magFieldEarth0 Serial UDB Extra Magnetic Field Earth 0 - * @param sue_magFieldEarth1 Serial UDB Extra Magnetic Field Earth 1 - * @param sue_magFieldEarth2 Serial UDB Extra Magnetic Field Earth 2 - * @param sue_svs Serial UDB Extra Number of Sattelites in View - * @param sue_hdop Serial UDB Extra GPS Horizontal Dilution of Precision - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f2_a_send(mavlink_channel_t chan, uint32_t sue_time, uint8_t sue_status, int32_t sue_latitude, int32_t sue_longitude, int32_t sue_altitude, uint16_t sue_waypoint_index, int16_t sue_rmat0, int16_t sue_rmat1, int16_t sue_rmat2, int16_t sue_rmat3, int16_t sue_rmat4, int16_t sue_rmat5, int16_t sue_rmat6, int16_t sue_rmat7, int16_t sue_rmat8, uint16_t sue_cog, int16_t sue_sog, uint16_t sue_cpu_load, int16_t sue_voltage_milis, uint16_t sue_air_speed_3DIMU, int16_t sue_estimated_wind_0, int16_t sue_estimated_wind_1, int16_t sue_estimated_wind_2, int16_t sue_magFieldEarth0, int16_t sue_magFieldEarth1, int16_t sue_magFieldEarth2, int16_t sue_svs, int16_t sue_hdop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN]; - _mav_put_uint32_t(buf, 0, sue_time); - _mav_put_int32_t(buf, 4, sue_latitude); - _mav_put_int32_t(buf, 8, sue_longitude); - _mav_put_int32_t(buf, 12, sue_altitude); - _mav_put_uint16_t(buf, 16, sue_waypoint_index); - _mav_put_int16_t(buf, 18, sue_rmat0); - _mav_put_int16_t(buf, 20, sue_rmat1); - _mav_put_int16_t(buf, 22, sue_rmat2); - _mav_put_int16_t(buf, 24, sue_rmat3); - _mav_put_int16_t(buf, 26, sue_rmat4); - _mav_put_int16_t(buf, 28, sue_rmat5); - _mav_put_int16_t(buf, 30, sue_rmat6); - _mav_put_int16_t(buf, 32, sue_rmat7); - _mav_put_int16_t(buf, 34, sue_rmat8); - _mav_put_uint16_t(buf, 36, sue_cog); - _mav_put_int16_t(buf, 38, sue_sog); - _mav_put_uint16_t(buf, 40, sue_cpu_load); - _mav_put_int16_t(buf, 42, sue_voltage_milis); - _mav_put_uint16_t(buf, 44, sue_air_speed_3DIMU); - _mav_put_int16_t(buf, 46, sue_estimated_wind_0); - _mav_put_int16_t(buf, 48, sue_estimated_wind_1); - _mav_put_int16_t(buf, 50, sue_estimated_wind_2); - _mav_put_int16_t(buf, 52, sue_magFieldEarth0); - _mav_put_int16_t(buf, 54, sue_magFieldEarth1); - _mav_put_int16_t(buf, 56, sue_magFieldEarth2); - _mav_put_int16_t(buf, 58, sue_svs); - _mav_put_int16_t(buf, 60, sue_hdop); - _mav_put_uint8_t(buf, 62, sue_status); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#endif -#else - mavlink_serial_udb_extra_f2_a_t packet; - packet.sue_time = sue_time; - packet.sue_latitude = sue_latitude; - packet.sue_longitude = sue_longitude; - packet.sue_altitude = sue_altitude; - packet.sue_waypoint_index = sue_waypoint_index; - packet.sue_rmat0 = sue_rmat0; - packet.sue_rmat1 = sue_rmat1; - packet.sue_rmat2 = sue_rmat2; - packet.sue_rmat3 = sue_rmat3; - packet.sue_rmat4 = sue_rmat4; - packet.sue_rmat5 = sue_rmat5; - packet.sue_rmat6 = sue_rmat6; - packet.sue_rmat7 = sue_rmat7; - packet.sue_rmat8 = sue_rmat8; - packet.sue_cog = sue_cog; - packet.sue_sog = sue_sog; - packet.sue_cpu_load = sue_cpu_load; - packet.sue_voltage_milis = sue_voltage_milis; - packet.sue_air_speed_3DIMU = sue_air_speed_3DIMU; - packet.sue_estimated_wind_0 = sue_estimated_wind_0; - packet.sue_estimated_wind_1 = sue_estimated_wind_1; - packet.sue_estimated_wind_2 = sue_estimated_wind_2; - packet.sue_magFieldEarth0 = sue_magFieldEarth0; - packet.sue_magFieldEarth1 = sue_magFieldEarth1; - packet.sue_magFieldEarth2 = sue_magFieldEarth2; - packet.sue_svs = sue_svs; - packet.sue_hdop = sue_hdop; - packet.sue_status = sue_status; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f2_a_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t sue_time, uint8_t sue_status, int32_t sue_latitude, int32_t sue_longitude, int32_t sue_altitude, uint16_t sue_waypoint_index, int16_t sue_rmat0, int16_t sue_rmat1, int16_t sue_rmat2, int16_t sue_rmat3, int16_t sue_rmat4, int16_t sue_rmat5, int16_t sue_rmat6, int16_t sue_rmat7, int16_t sue_rmat8, uint16_t sue_cog, int16_t sue_sog, uint16_t sue_cpu_load, int16_t sue_voltage_milis, uint16_t sue_air_speed_3DIMU, int16_t sue_estimated_wind_0, int16_t sue_estimated_wind_1, int16_t sue_estimated_wind_2, int16_t sue_magFieldEarth0, int16_t sue_magFieldEarth1, int16_t sue_magFieldEarth2, int16_t sue_svs, int16_t sue_hdop) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, sue_time); - _mav_put_int32_t(buf, 4, sue_latitude); - _mav_put_int32_t(buf, 8, sue_longitude); - _mav_put_int32_t(buf, 12, sue_altitude); - _mav_put_uint16_t(buf, 16, sue_waypoint_index); - _mav_put_int16_t(buf, 18, sue_rmat0); - _mav_put_int16_t(buf, 20, sue_rmat1); - _mav_put_int16_t(buf, 22, sue_rmat2); - _mav_put_int16_t(buf, 24, sue_rmat3); - _mav_put_int16_t(buf, 26, sue_rmat4); - _mav_put_int16_t(buf, 28, sue_rmat5); - _mav_put_int16_t(buf, 30, sue_rmat6); - _mav_put_int16_t(buf, 32, sue_rmat7); - _mav_put_int16_t(buf, 34, sue_rmat8); - _mav_put_uint16_t(buf, 36, sue_cog); - _mav_put_int16_t(buf, 38, sue_sog); - _mav_put_uint16_t(buf, 40, sue_cpu_load); - _mav_put_int16_t(buf, 42, sue_voltage_milis); - _mav_put_uint16_t(buf, 44, sue_air_speed_3DIMU); - _mav_put_int16_t(buf, 46, sue_estimated_wind_0); - _mav_put_int16_t(buf, 48, sue_estimated_wind_1); - _mav_put_int16_t(buf, 50, sue_estimated_wind_2); - _mav_put_int16_t(buf, 52, sue_magFieldEarth0); - _mav_put_int16_t(buf, 54, sue_magFieldEarth1); - _mav_put_int16_t(buf, 56, sue_magFieldEarth2); - _mav_put_int16_t(buf, 58, sue_svs); - _mav_put_int16_t(buf, 60, sue_hdop); - _mav_put_uint8_t(buf, 62, sue_status); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#endif -#else - mavlink_serial_udb_extra_f2_a_t *packet = (mavlink_serial_udb_extra_f2_a_t *)msgbuf; - packet->sue_time = sue_time; - packet->sue_latitude = sue_latitude; - packet->sue_longitude = sue_longitude; - packet->sue_altitude = sue_altitude; - packet->sue_waypoint_index = sue_waypoint_index; - packet->sue_rmat0 = sue_rmat0; - packet->sue_rmat1 = sue_rmat1; - packet->sue_rmat2 = sue_rmat2; - packet->sue_rmat3 = sue_rmat3; - packet->sue_rmat4 = sue_rmat4; - packet->sue_rmat5 = sue_rmat5; - packet->sue_rmat6 = sue_rmat6; - packet->sue_rmat7 = sue_rmat7; - packet->sue_rmat8 = sue_rmat8; - packet->sue_cog = sue_cog; - packet->sue_sog = sue_sog; - packet->sue_cpu_load = sue_cpu_load; - packet->sue_voltage_milis = sue_voltage_milis; - packet->sue_air_speed_3DIMU = sue_air_speed_3DIMU; - packet->sue_estimated_wind_0 = sue_estimated_wind_0; - packet->sue_estimated_wind_1 = sue_estimated_wind_1; - packet->sue_estimated_wind_2 = sue_estimated_wind_2; - packet->sue_magFieldEarth0 = sue_magFieldEarth0; - packet->sue_magFieldEarth1 = sue_magFieldEarth1; - packet->sue_magFieldEarth2 = sue_magFieldEarth2; - packet->sue_svs = sue_svs; - packet->sue_hdop = sue_hdop; - packet->sue_status = sue_status; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F2_A UNPACKING - - -/** - * @brief Get field sue_time from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Time - */ -static inline uint32_t mavlink_msg_serial_udb_extra_f2_a_get_sue_time(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field sue_status from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Status - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f2_a_get_sue_status(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 62); -} - -/** - * @brief Get field sue_latitude from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Latitude - */ -static inline int32_t mavlink_msg_serial_udb_extra_f2_a_get_sue_latitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field sue_longitude from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Longitude - */ -static inline int32_t mavlink_msg_serial_udb_extra_f2_a_get_sue_longitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Get field sue_altitude from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Altitude - */ -static inline int32_t mavlink_msg_serial_udb_extra_f2_a_get_sue_altitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 12); -} - -/** - * @brief Get field sue_waypoint_index from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Waypoint Index - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_waypoint_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field sue_rmat0 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Rmat 0 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field sue_rmat1 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Rmat 1 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field sue_rmat2 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Rmat 2 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field sue_rmat3 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Rmat 3 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Get field sue_rmat4 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Rmat 4 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 26); -} - -/** - * @brief Get field sue_rmat5 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Rmat 5 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 28); -} - -/** - * @brief Get field sue_rmat6 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Rmat 6 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 30); -} - -/** - * @brief Get field sue_rmat7 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Rmat 7 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 32); -} - -/** - * @brief Get field sue_rmat8 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Rmat 8 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 34); -} - -/** - * @brief Get field sue_cog from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra GPS Course Over Ground - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_cog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 36); -} - -/** - * @brief Get field sue_sog from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Speed Over Ground - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_sog(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 38); -} - -/** - * @brief Get field sue_cpu_load from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra CPU Load - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_cpu_load(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 40); -} - -/** - * @brief Get field sue_voltage_milis from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Voltage in MilliVolts - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_voltage_milis(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 42); -} - -/** - * @brief Get field sue_air_speed_3DIMU from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra 3D IMU Air Speed - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_air_speed_3DIMU(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 44); -} - -/** - * @brief Get field sue_estimated_wind_0 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Estimated Wind 0 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 46); -} - -/** - * @brief Get field sue_estimated_wind_1 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Estimated Wind 1 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field sue_estimated_wind_2 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Estimated Wind 2 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field sue_magFieldEarth0 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Magnetic Field Earth 0 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth0(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field sue_magFieldEarth1 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Magnetic Field Earth 1 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 54); -} - -/** - * @brief Get field sue_magFieldEarth2 from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Magnetic Field Earth 2 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 56); -} - -/** - * @brief Get field sue_svs from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra Number of Sattelites in View - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_svs(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 58); -} - -/** - * @brief Get field sue_hdop from serial_udb_extra_f2_a message - * - * @return Serial UDB Extra GPS Horizontal Dilution of Precision - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_a_get_sue_hdop(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 60); -} - -/** - * @brief Decode a serial_udb_extra_f2_a message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f2_a C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f2_a_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f2_a_t* serial_udb_extra_f2_a) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_udb_extra_f2_a->sue_time = mavlink_msg_serial_udb_extra_f2_a_get_sue_time(msg); - serial_udb_extra_f2_a->sue_latitude = mavlink_msg_serial_udb_extra_f2_a_get_sue_latitude(msg); - serial_udb_extra_f2_a->sue_longitude = mavlink_msg_serial_udb_extra_f2_a_get_sue_longitude(msg); - serial_udb_extra_f2_a->sue_altitude = mavlink_msg_serial_udb_extra_f2_a_get_sue_altitude(msg); - serial_udb_extra_f2_a->sue_waypoint_index = mavlink_msg_serial_udb_extra_f2_a_get_sue_waypoint_index(msg); - serial_udb_extra_f2_a->sue_rmat0 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat0(msg); - serial_udb_extra_f2_a->sue_rmat1 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat1(msg); - serial_udb_extra_f2_a->sue_rmat2 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat2(msg); - serial_udb_extra_f2_a->sue_rmat3 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat3(msg); - serial_udb_extra_f2_a->sue_rmat4 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat4(msg); - serial_udb_extra_f2_a->sue_rmat5 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat5(msg); - serial_udb_extra_f2_a->sue_rmat6 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat6(msg); - serial_udb_extra_f2_a->sue_rmat7 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat7(msg); - serial_udb_extra_f2_a->sue_rmat8 = mavlink_msg_serial_udb_extra_f2_a_get_sue_rmat8(msg); - serial_udb_extra_f2_a->sue_cog = mavlink_msg_serial_udb_extra_f2_a_get_sue_cog(msg); - serial_udb_extra_f2_a->sue_sog = mavlink_msg_serial_udb_extra_f2_a_get_sue_sog(msg); - serial_udb_extra_f2_a->sue_cpu_load = mavlink_msg_serial_udb_extra_f2_a_get_sue_cpu_load(msg); - serial_udb_extra_f2_a->sue_voltage_milis = mavlink_msg_serial_udb_extra_f2_a_get_sue_voltage_milis(msg); - serial_udb_extra_f2_a->sue_air_speed_3DIMU = mavlink_msg_serial_udb_extra_f2_a_get_sue_air_speed_3DIMU(msg); - serial_udb_extra_f2_a->sue_estimated_wind_0 = mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_0(msg); - serial_udb_extra_f2_a->sue_estimated_wind_1 = mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_1(msg); - serial_udb_extra_f2_a->sue_estimated_wind_2 = mavlink_msg_serial_udb_extra_f2_a_get_sue_estimated_wind_2(msg); - serial_udb_extra_f2_a->sue_magFieldEarth0 = mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth0(msg); - serial_udb_extra_f2_a->sue_magFieldEarth1 = mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth1(msg); - serial_udb_extra_f2_a->sue_magFieldEarth2 = mavlink_msg_serial_udb_extra_f2_a_get_sue_magFieldEarth2(msg); - serial_udb_extra_f2_a->sue_svs = mavlink_msg_serial_udb_extra_f2_a_get_sue_svs(msg); - serial_udb_extra_f2_a->sue_hdop = mavlink_msg_serial_udb_extra_f2_a_get_sue_hdop(msg); - serial_udb_extra_f2_a->sue_status = mavlink_msg_serial_udb_extra_f2_a_get_sue_status(msg); -#else - memcpy(serial_udb_extra_f2_a, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_A_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h deleted file mode 100644 index 3e1757f74..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f2_b.h +++ /dev/null @@ -1,977 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F2_B PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B 171 - -typedef struct __mavlink_serial_udb_extra_f2_b_t -{ - uint32_t sue_time; ///< Serial UDB Extra Time - uint32_t sue_flags; ///< Serial UDB Extra Status Flags - int16_t sue_pwm_input_1; ///< Serial UDB Extra PWM Input Channel 1 - int16_t sue_pwm_input_2; ///< Serial UDB Extra PWM Input Channel 2 - int16_t sue_pwm_input_3; ///< Serial UDB Extra PWM Input Channel 3 - int16_t sue_pwm_input_4; ///< Serial UDB Extra PWM Input Channel 4 - int16_t sue_pwm_input_5; ///< Serial UDB Extra PWM Input Channel 5 - int16_t sue_pwm_input_6; ///< Serial UDB Extra PWM Input Channel 6 - int16_t sue_pwm_input_7; ///< Serial UDB Extra PWM Input Channel 7 - int16_t sue_pwm_input_8; ///< Serial UDB Extra PWM Input Channel 8 - int16_t sue_pwm_input_9; ///< Serial UDB Extra PWM Input Channel 9 - int16_t sue_pwm_input_10; ///< Serial UDB Extra PWM Input Channel 10 - int16_t sue_pwm_output_1; ///< Serial UDB Extra PWM Output Channel 1 - int16_t sue_pwm_output_2; ///< Serial UDB Extra PWM Output Channel 2 - int16_t sue_pwm_output_3; ///< Serial UDB Extra PWM Output Channel 3 - int16_t sue_pwm_output_4; ///< Serial UDB Extra PWM Output Channel 4 - int16_t sue_pwm_output_5; ///< Serial UDB Extra PWM Output Channel 5 - int16_t sue_pwm_output_6; ///< Serial UDB Extra PWM Output Channel 6 - int16_t sue_pwm_output_7; ///< Serial UDB Extra PWM Output Channel 7 - int16_t sue_pwm_output_8; ///< Serial UDB Extra PWM Output Channel 8 - int16_t sue_pwm_output_9; ///< Serial UDB Extra PWM Output Channel 9 - int16_t sue_pwm_output_10; ///< Serial UDB Extra PWM Output Channel 10 - int16_t sue_imu_location_x; ///< Serial UDB Extra IMU Location X - int16_t sue_imu_location_y; ///< Serial UDB Extra IMU Location Y - int16_t sue_imu_location_z; ///< Serial UDB Extra IMU Location Z - int16_t sue_osc_fails; ///< Serial UDB Extra Oscillator Failure Count - int16_t sue_imu_velocity_x; ///< Serial UDB Extra IMU Velocity X - int16_t sue_imu_velocity_y; ///< Serial UDB Extra IMU Velocity Y - int16_t sue_imu_velocity_z; ///< Serial UDB Extra IMU Velocity Z - int16_t sue_waypoint_goal_x; ///< Serial UDB Extra Current Waypoint Goal X - int16_t sue_waypoint_goal_y; ///< Serial UDB Extra Current Waypoint Goal Y - int16_t sue_waypoint_goal_z; ///< Serial UDB Extra Current Waypoint Goal Z - int16_t sue_memory_stack_free; ///< Serial UDB Extra Stack Memory Free -} mavlink_serial_udb_extra_f2_b_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN 70 -#define MAVLINK_MSG_ID_171_LEN 70 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC 169 -#define MAVLINK_MSG_ID_171_CRC 169 - - - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F2_B { \ - "SERIAL_UDB_EXTRA_F2_B", \ - 33, \ - { { "sue_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_time) }, \ - { "sue_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_flags) }, \ - { "sue_pwm_input_1", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_1) }, \ - { "sue_pwm_input_2", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_2) }, \ - { "sue_pwm_input_3", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_3) }, \ - { "sue_pwm_input_4", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_4) }, \ - { "sue_pwm_input_5", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_5) }, \ - { "sue_pwm_input_6", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_6) }, \ - { "sue_pwm_input_7", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_7) }, \ - { "sue_pwm_input_8", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_8) }, \ - { "sue_pwm_input_9", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_9) }, \ - { "sue_pwm_input_10", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_input_10) }, \ - { "sue_pwm_output_1", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_1) }, \ - { "sue_pwm_output_2", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_2) }, \ - { "sue_pwm_output_3", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_3) }, \ - { "sue_pwm_output_4", NULL, MAVLINK_TYPE_INT16_T, 0, 34, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_4) }, \ - { "sue_pwm_output_5", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_5) }, \ - { "sue_pwm_output_6", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_6) }, \ - { "sue_pwm_output_7", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_7) }, \ - { "sue_pwm_output_8", NULL, MAVLINK_TYPE_INT16_T, 0, 42, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_8) }, \ - { "sue_pwm_output_9", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_9) }, \ - { "sue_pwm_output_10", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_pwm_output_10) }, \ - { "sue_imu_location_x", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_location_x) }, \ - { "sue_imu_location_y", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_location_y) }, \ - { "sue_imu_location_z", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_location_z) }, \ - { "sue_osc_fails", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_osc_fails) }, \ - { "sue_imu_velocity_x", NULL, MAVLINK_TYPE_INT16_T, 0, 56, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_velocity_x) }, \ - { "sue_imu_velocity_y", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_velocity_y) }, \ - { "sue_imu_velocity_z", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_imu_velocity_z) }, \ - { "sue_waypoint_goal_x", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_waypoint_goal_x) }, \ - { "sue_waypoint_goal_y", NULL, MAVLINK_TYPE_INT16_T, 0, 64, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_waypoint_goal_y) }, \ - { "sue_waypoint_goal_z", NULL, MAVLINK_TYPE_INT16_T, 0, 66, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_waypoint_goal_z) }, \ - { "sue_memory_stack_free", NULL, MAVLINK_TYPE_INT16_T, 0, 68, offsetof(mavlink_serial_udb_extra_f2_b_t, sue_memory_stack_free) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f2_b message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_time Serial UDB Extra Time - * @param sue_pwm_input_1 Serial UDB Extra PWM Input Channel 1 - * @param sue_pwm_input_2 Serial UDB Extra PWM Input Channel 2 - * @param sue_pwm_input_3 Serial UDB Extra PWM Input Channel 3 - * @param sue_pwm_input_4 Serial UDB Extra PWM Input Channel 4 - * @param sue_pwm_input_5 Serial UDB Extra PWM Input Channel 5 - * @param sue_pwm_input_6 Serial UDB Extra PWM Input Channel 6 - * @param sue_pwm_input_7 Serial UDB Extra PWM Input Channel 7 - * @param sue_pwm_input_8 Serial UDB Extra PWM Input Channel 8 - * @param sue_pwm_input_9 Serial UDB Extra PWM Input Channel 9 - * @param sue_pwm_input_10 Serial UDB Extra PWM Input Channel 10 - * @param sue_pwm_output_1 Serial UDB Extra PWM Output Channel 1 - * @param sue_pwm_output_2 Serial UDB Extra PWM Output Channel 2 - * @param sue_pwm_output_3 Serial UDB Extra PWM Output Channel 3 - * @param sue_pwm_output_4 Serial UDB Extra PWM Output Channel 4 - * @param sue_pwm_output_5 Serial UDB Extra PWM Output Channel 5 - * @param sue_pwm_output_6 Serial UDB Extra PWM Output Channel 6 - * @param sue_pwm_output_7 Serial UDB Extra PWM Output Channel 7 - * @param sue_pwm_output_8 Serial UDB Extra PWM Output Channel 8 - * @param sue_pwm_output_9 Serial UDB Extra PWM Output Channel 9 - * @param sue_pwm_output_10 Serial UDB Extra PWM Output Channel 10 - * @param sue_imu_location_x Serial UDB Extra IMU Location X - * @param sue_imu_location_y Serial UDB Extra IMU Location Y - * @param sue_imu_location_z Serial UDB Extra IMU Location Z - * @param sue_flags Serial UDB Extra Status Flags - * @param sue_osc_fails Serial UDB Extra Oscillator Failure Count - * @param sue_imu_velocity_x Serial UDB Extra IMU Velocity X - * @param sue_imu_velocity_y Serial UDB Extra IMU Velocity Y - * @param sue_imu_velocity_z Serial UDB Extra IMU Velocity Z - * @param sue_waypoint_goal_x Serial UDB Extra Current Waypoint Goal X - * @param sue_waypoint_goal_y Serial UDB Extra Current Waypoint Goal Y - * @param sue_waypoint_goal_z Serial UDB Extra Current Waypoint Goal Z - * @param sue_memory_stack_free Serial UDB Extra Stack Memory Free - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t sue_time, int16_t sue_pwm_input_1, int16_t sue_pwm_input_2, int16_t sue_pwm_input_3, int16_t sue_pwm_input_4, int16_t sue_pwm_input_5, int16_t sue_pwm_input_6, int16_t sue_pwm_input_7, int16_t sue_pwm_input_8, int16_t sue_pwm_input_9, int16_t sue_pwm_input_10, int16_t sue_pwm_output_1, int16_t sue_pwm_output_2, int16_t sue_pwm_output_3, int16_t sue_pwm_output_4, int16_t sue_pwm_output_5, int16_t sue_pwm_output_6, int16_t sue_pwm_output_7, int16_t sue_pwm_output_8, int16_t sue_pwm_output_9, int16_t sue_pwm_output_10, int16_t sue_imu_location_x, int16_t sue_imu_location_y, int16_t sue_imu_location_z, uint32_t sue_flags, int16_t sue_osc_fails, int16_t sue_imu_velocity_x, int16_t sue_imu_velocity_y, int16_t sue_imu_velocity_z, int16_t sue_waypoint_goal_x, int16_t sue_waypoint_goal_y, int16_t sue_waypoint_goal_z, int16_t sue_memory_stack_free) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN]; - _mav_put_uint32_t(buf, 0, sue_time); - _mav_put_uint32_t(buf, 4, sue_flags); - _mav_put_int16_t(buf, 8, sue_pwm_input_1); - _mav_put_int16_t(buf, 10, sue_pwm_input_2); - _mav_put_int16_t(buf, 12, sue_pwm_input_3); - _mav_put_int16_t(buf, 14, sue_pwm_input_4); - _mav_put_int16_t(buf, 16, sue_pwm_input_5); - _mav_put_int16_t(buf, 18, sue_pwm_input_6); - _mav_put_int16_t(buf, 20, sue_pwm_input_7); - _mav_put_int16_t(buf, 22, sue_pwm_input_8); - _mav_put_int16_t(buf, 24, sue_pwm_input_9); - _mav_put_int16_t(buf, 26, sue_pwm_input_10); - _mav_put_int16_t(buf, 28, sue_pwm_output_1); - _mav_put_int16_t(buf, 30, sue_pwm_output_2); - _mav_put_int16_t(buf, 32, sue_pwm_output_3); - _mav_put_int16_t(buf, 34, sue_pwm_output_4); - _mav_put_int16_t(buf, 36, sue_pwm_output_5); - _mav_put_int16_t(buf, 38, sue_pwm_output_6); - _mav_put_int16_t(buf, 40, sue_pwm_output_7); - _mav_put_int16_t(buf, 42, sue_pwm_output_8); - _mav_put_int16_t(buf, 44, sue_pwm_output_9); - _mav_put_int16_t(buf, 46, sue_pwm_output_10); - _mav_put_int16_t(buf, 48, sue_imu_location_x); - _mav_put_int16_t(buf, 50, sue_imu_location_y); - _mav_put_int16_t(buf, 52, sue_imu_location_z); - _mav_put_int16_t(buf, 54, sue_osc_fails); - _mav_put_int16_t(buf, 56, sue_imu_velocity_x); - _mav_put_int16_t(buf, 58, sue_imu_velocity_y); - _mav_put_int16_t(buf, 60, sue_imu_velocity_z); - _mav_put_int16_t(buf, 62, sue_waypoint_goal_x); - _mav_put_int16_t(buf, 64, sue_waypoint_goal_y); - _mav_put_int16_t(buf, 66, sue_waypoint_goal_z); - _mav_put_int16_t(buf, 68, sue_memory_stack_free); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#else - mavlink_serial_udb_extra_f2_b_t packet; - packet.sue_time = sue_time; - packet.sue_flags = sue_flags; - packet.sue_pwm_input_1 = sue_pwm_input_1; - packet.sue_pwm_input_2 = sue_pwm_input_2; - packet.sue_pwm_input_3 = sue_pwm_input_3; - packet.sue_pwm_input_4 = sue_pwm_input_4; - packet.sue_pwm_input_5 = sue_pwm_input_5; - packet.sue_pwm_input_6 = sue_pwm_input_6; - packet.sue_pwm_input_7 = sue_pwm_input_7; - packet.sue_pwm_input_8 = sue_pwm_input_8; - packet.sue_pwm_input_9 = sue_pwm_input_9; - packet.sue_pwm_input_10 = sue_pwm_input_10; - packet.sue_pwm_output_1 = sue_pwm_output_1; - packet.sue_pwm_output_2 = sue_pwm_output_2; - packet.sue_pwm_output_3 = sue_pwm_output_3; - packet.sue_pwm_output_4 = sue_pwm_output_4; - packet.sue_pwm_output_5 = sue_pwm_output_5; - packet.sue_pwm_output_6 = sue_pwm_output_6; - packet.sue_pwm_output_7 = sue_pwm_output_7; - packet.sue_pwm_output_8 = sue_pwm_output_8; - packet.sue_pwm_output_9 = sue_pwm_output_9; - packet.sue_pwm_output_10 = sue_pwm_output_10; - packet.sue_imu_location_x = sue_imu_location_x; - packet.sue_imu_location_y = sue_imu_location_y; - packet.sue_imu_location_z = sue_imu_location_z; - packet.sue_osc_fails = sue_osc_fails; - packet.sue_imu_velocity_x = sue_imu_velocity_x; - packet.sue_imu_velocity_y = sue_imu_velocity_y; - packet.sue_imu_velocity_z = sue_imu_velocity_z; - packet.sue_waypoint_goal_x = sue_waypoint_goal_x; - packet.sue_waypoint_goal_y = sue_waypoint_goal_y; - packet.sue_waypoint_goal_z = sue_waypoint_goal_z; - packet.sue_memory_stack_free = sue_memory_stack_free; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f2_b message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_time Serial UDB Extra Time - * @param sue_pwm_input_1 Serial UDB Extra PWM Input Channel 1 - * @param sue_pwm_input_2 Serial UDB Extra PWM Input Channel 2 - * @param sue_pwm_input_3 Serial UDB Extra PWM Input Channel 3 - * @param sue_pwm_input_4 Serial UDB Extra PWM Input Channel 4 - * @param sue_pwm_input_5 Serial UDB Extra PWM Input Channel 5 - * @param sue_pwm_input_6 Serial UDB Extra PWM Input Channel 6 - * @param sue_pwm_input_7 Serial UDB Extra PWM Input Channel 7 - * @param sue_pwm_input_8 Serial UDB Extra PWM Input Channel 8 - * @param sue_pwm_input_9 Serial UDB Extra PWM Input Channel 9 - * @param sue_pwm_input_10 Serial UDB Extra PWM Input Channel 10 - * @param sue_pwm_output_1 Serial UDB Extra PWM Output Channel 1 - * @param sue_pwm_output_2 Serial UDB Extra PWM Output Channel 2 - * @param sue_pwm_output_3 Serial UDB Extra PWM Output Channel 3 - * @param sue_pwm_output_4 Serial UDB Extra PWM Output Channel 4 - * @param sue_pwm_output_5 Serial UDB Extra PWM Output Channel 5 - * @param sue_pwm_output_6 Serial UDB Extra PWM Output Channel 6 - * @param sue_pwm_output_7 Serial UDB Extra PWM Output Channel 7 - * @param sue_pwm_output_8 Serial UDB Extra PWM Output Channel 8 - * @param sue_pwm_output_9 Serial UDB Extra PWM Output Channel 9 - * @param sue_pwm_output_10 Serial UDB Extra PWM Output Channel 10 - * @param sue_imu_location_x Serial UDB Extra IMU Location X - * @param sue_imu_location_y Serial UDB Extra IMU Location Y - * @param sue_imu_location_z Serial UDB Extra IMU Location Z - * @param sue_flags Serial UDB Extra Status Flags - * @param sue_osc_fails Serial UDB Extra Oscillator Failure Count - * @param sue_imu_velocity_x Serial UDB Extra IMU Velocity X - * @param sue_imu_velocity_y Serial UDB Extra IMU Velocity Y - * @param sue_imu_velocity_z Serial UDB Extra IMU Velocity Z - * @param sue_waypoint_goal_x Serial UDB Extra Current Waypoint Goal X - * @param sue_waypoint_goal_y Serial UDB Extra Current Waypoint Goal Y - * @param sue_waypoint_goal_z Serial UDB Extra Current Waypoint Goal Z - * @param sue_memory_stack_free Serial UDB Extra Stack Memory Free - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint32_t sue_time,int16_t sue_pwm_input_1,int16_t sue_pwm_input_2,int16_t sue_pwm_input_3,int16_t sue_pwm_input_4,int16_t sue_pwm_input_5,int16_t sue_pwm_input_6,int16_t sue_pwm_input_7,int16_t sue_pwm_input_8,int16_t sue_pwm_input_9,int16_t sue_pwm_input_10,int16_t sue_pwm_output_1,int16_t sue_pwm_output_2,int16_t sue_pwm_output_3,int16_t sue_pwm_output_4,int16_t sue_pwm_output_5,int16_t sue_pwm_output_6,int16_t sue_pwm_output_7,int16_t sue_pwm_output_8,int16_t sue_pwm_output_9,int16_t sue_pwm_output_10,int16_t sue_imu_location_x,int16_t sue_imu_location_y,int16_t sue_imu_location_z,uint32_t sue_flags,int16_t sue_osc_fails,int16_t sue_imu_velocity_x,int16_t sue_imu_velocity_y,int16_t sue_imu_velocity_z,int16_t sue_waypoint_goal_x,int16_t sue_waypoint_goal_y,int16_t sue_waypoint_goal_z,int16_t sue_memory_stack_free) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN]; - _mav_put_uint32_t(buf, 0, sue_time); - _mav_put_uint32_t(buf, 4, sue_flags); - _mav_put_int16_t(buf, 8, sue_pwm_input_1); - _mav_put_int16_t(buf, 10, sue_pwm_input_2); - _mav_put_int16_t(buf, 12, sue_pwm_input_3); - _mav_put_int16_t(buf, 14, sue_pwm_input_4); - _mav_put_int16_t(buf, 16, sue_pwm_input_5); - _mav_put_int16_t(buf, 18, sue_pwm_input_6); - _mav_put_int16_t(buf, 20, sue_pwm_input_7); - _mav_put_int16_t(buf, 22, sue_pwm_input_8); - _mav_put_int16_t(buf, 24, sue_pwm_input_9); - _mav_put_int16_t(buf, 26, sue_pwm_input_10); - _mav_put_int16_t(buf, 28, sue_pwm_output_1); - _mav_put_int16_t(buf, 30, sue_pwm_output_2); - _mav_put_int16_t(buf, 32, sue_pwm_output_3); - _mav_put_int16_t(buf, 34, sue_pwm_output_4); - _mav_put_int16_t(buf, 36, sue_pwm_output_5); - _mav_put_int16_t(buf, 38, sue_pwm_output_6); - _mav_put_int16_t(buf, 40, sue_pwm_output_7); - _mav_put_int16_t(buf, 42, sue_pwm_output_8); - _mav_put_int16_t(buf, 44, sue_pwm_output_9); - _mav_put_int16_t(buf, 46, sue_pwm_output_10); - _mav_put_int16_t(buf, 48, sue_imu_location_x); - _mav_put_int16_t(buf, 50, sue_imu_location_y); - _mav_put_int16_t(buf, 52, sue_imu_location_z); - _mav_put_int16_t(buf, 54, sue_osc_fails); - _mav_put_int16_t(buf, 56, sue_imu_velocity_x); - _mav_put_int16_t(buf, 58, sue_imu_velocity_y); - _mav_put_int16_t(buf, 60, sue_imu_velocity_z); - _mav_put_int16_t(buf, 62, sue_waypoint_goal_x); - _mav_put_int16_t(buf, 64, sue_waypoint_goal_y); - _mav_put_int16_t(buf, 66, sue_waypoint_goal_z); - _mav_put_int16_t(buf, 68, sue_memory_stack_free); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#else - mavlink_serial_udb_extra_f2_b_t packet; - packet.sue_time = sue_time; - packet.sue_flags = sue_flags; - packet.sue_pwm_input_1 = sue_pwm_input_1; - packet.sue_pwm_input_2 = sue_pwm_input_2; - packet.sue_pwm_input_3 = sue_pwm_input_3; - packet.sue_pwm_input_4 = sue_pwm_input_4; - packet.sue_pwm_input_5 = sue_pwm_input_5; - packet.sue_pwm_input_6 = sue_pwm_input_6; - packet.sue_pwm_input_7 = sue_pwm_input_7; - packet.sue_pwm_input_8 = sue_pwm_input_8; - packet.sue_pwm_input_9 = sue_pwm_input_9; - packet.sue_pwm_input_10 = sue_pwm_input_10; - packet.sue_pwm_output_1 = sue_pwm_output_1; - packet.sue_pwm_output_2 = sue_pwm_output_2; - packet.sue_pwm_output_3 = sue_pwm_output_3; - packet.sue_pwm_output_4 = sue_pwm_output_4; - packet.sue_pwm_output_5 = sue_pwm_output_5; - packet.sue_pwm_output_6 = sue_pwm_output_6; - packet.sue_pwm_output_7 = sue_pwm_output_7; - packet.sue_pwm_output_8 = sue_pwm_output_8; - packet.sue_pwm_output_9 = sue_pwm_output_9; - packet.sue_pwm_output_10 = sue_pwm_output_10; - packet.sue_imu_location_x = sue_imu_location_x; - packet.sue_imu_location_y = sue_imu_location_y; - packet.sue_imu_location_z = sue_imu_location_z; - packet.sue_osc_fails = sue_osc_fails; - packet.sue_imu_velocity_x = sue_imu_velocity_x; - packet.sue_imu_velocity_y = sue_imu_velocity_y; - packet.sue_imu_velocity_z = sue_imu_velocity_z; - packet.sue_waypoint_goal_x = sue_waypoint_goal_x; - packet.sue_waypoint_goal_y = sue_waypoint_goal_y; - packet.sue_waypoint_goal_z = sue_waypoint_goal_z; - packet.sue_memory_stack_free = sue_memory_stack_free; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f2_b struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f2_b C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f2_b_t* serial_udb_extra_f2_b) -{ - return mavlink_msg_serial_udb_extra_f2_b_pack(system_id, component_id, msg, serial_udb_extra_f2_b->sue_time, serial_udb_extra_f2_b->sue_pwm_input_1, serial_udb_extra_f2_b->sue_pwm_input_2, serial_udb_extra_f2_b->sue_pwm_input_3, serial_udb_extra_f2_b->sue_pwm_input_4, serial_udb_extra_f2_b->sue_pwm_input_5, serial_udb_extra_f2_b->sue_pwm_input_6, serial_udb_extra_f2_b->sue_pwm_input_7, serial_udb_extra_f2_b->sue_pwm_input_8, serial_udb_extra_f2_b->sue_pwm_input_9, serial_udb_extra_f2_b->sue_pwm_input_10, serial_udb_extra_f2_b->sue_pwm_output_1, serial_udb_extra_f2_b->sue_pwm_output_2, serial_udb_extra_f2_b->sue_pwm_output_3, serial_udb_extra_f2_b->sue_pwm_output_4, serial_udb_extra_f2_b->sue_pwm_output_5, serial_udb_extra_f2_b->sue_pwm_output_6, serial_udb_extra_f2_b->sue_pwm_output_7, serial_udb_extra_f2_b->sue_pwm_output_8, serial_udb_extra_f2_b->sue_pwm_output_9, serial_udb_extra_f2_b->sue_pwm_output_10, serial_udb_extra_f2_b->sue_imu_location_x, serial_udb_extra_f2_b->sue_imu_location_y, serial_udb_extra_f2_b->sue_imu_location_z, serial_udb_extra_f2_b->sue_flags, serial_udb_extra_f2_b->sue_osc_fails, serial_udb_extra_f2_b->sue_imu_velocity_x, serial_udb_extra_f2_b->sue_imu_velocity_y, serial_udb_extra_f2_b->sue_imu_velocity_z, serial_udb_extra_f2_b->sue_waypoint_goal_x, serial_udb_extra_f2_b->sue_waypoint_goal_y, serial_udb_extra_f2_b->sue_waypoint_goal_z, serial_udb_extra_f2_b->sue_memory_stack_free); -} - -/** - * @brief Encode a serial_udb_extra_f2_b struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f2_b C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f2_b_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f2_b_t* serial_udb_extra_f2_b) -{ - return mavlink_msg_serial_udb_extra_f2_b_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f2_b->sue_time, serial_udb_extra_f2_b->sue_pwm_input_1, serial_udb_extra_f2_b->sue_pwm_input_2, serial_udb_extra_f2_b->sue_pwm_input_3, serial_udb_extra_f2_b->sue_pwm_input_4, serial_udb_extra_f2_b->sue_pwm_input_5, serial_udb_extra_f2_b->sue_pwm_input_6, serial_udb_extra_f2_b->sue_pwm_input_7, serial_udb_extra_f2_b->sue_pwm_input_8, serial_udb_extra_f2_b->sue_pwm_input_9, serial_udb_extra_f2_b->sue_pwm_input_10, serial_udb_extra_f2_b->sue_pwm_output_1, serial_udb_extra_f2_b->sue_pwm_output_2, serial_udb_extra_f2_b->sue_pwm_output_3, serial_udb_extra_f2_b->sue_pwm_output_4, serial_udb_extra_f2_b->sue_pwm_output_5, serial_udb_extra_f2_b->sue_pwm_output_6, serial_udb_extra_f2_b->sue_pwm_output_7, serial_udb_extra_f2_b->sue_pwm_output_8, serial_udb_extra_f2_b->sue_pwm_output_9, serial_udb_extra_f2_b->sue_pwm_output_10, serial_udb_extra_f2_b->sue_imu_location_x, serial_udb_extra_f2_b->sue_imu_location_y, serial_udb_extra_f2_b->sue_imu_location_z, serial_udb_extra_f2_b->sue_flags, serial_udb_extra_f2_b->sue_osc_fails, serial_udb_extra_f2_b->sue_imu_velocity_x, serial_udb_extra_f2_b->sue_imu_velocity_y, serial_udb_extra_f2_b->sue_imu_velocity_z, serial_udb_extra_f2_b->sue_waypoint_goal_x, serial_udb_extra_f2_b->sue_waypoint_goal_y, serial_udb_extra_f2_b->sue_waypoint_goal_z, serial_udb_extra_f2_b->sue_memory_stack_free); -} - -/** - * @brief Send a serial_udb_extra_f2_b message - * @param chan MAVLink channel to send the message - * - * @param sue_time Serial UDB Extra Time - * @param sue_pwm_input_1 Serial UDB Extra PWM Input Channel 1 - * @param sue_pwm_input_2 Serial UDB Extra PWM Input Channel 2 - * @param sue_pwm_input_3 Serial UDB Extra PWM Input Channel 3 - * @param sue_pwm_input_4 Serial UDB Extra PWM Input Channel 4 - * @param sue_pwm_input_5 Serial UDB Extra PWM Input Channel 5 - * @param sue_pwm_input_6 Serial UDB Extra PWM Input Channel 6 - * @param sue_pwm_input_7 Serial UDB Extra PWM Input Channel 7 - * @param sue_pwm_input_8 Serial UDB Extra PWM Input Channel 8 - * @param sue_pwm_input_9 Serial UDB Extra PWM Input Channel 9 - * @param sue_pwm_input_10 Serial UDB Extra PWM Input Channel 10 - * @param sue_pwm_output_1 Serial UDB Extra PWM Output Channel 1 - * @param sue_pwm_output_2 Serial UDB Extra PWM Output Channel 2 - * @param sue_pwm_output_3 Serial UDB Extra PWM Output Channel 3 - * @param sue_pwm_output_4 Serial UDB Extra PWM Output Channel 4 - * @param sue_pwm_output_5 Serial UDB Extra PWM Output Channel 5 - * @param sue_pwm_output_6 Serial UDB Extra PWM Output Channel 6 - * @param sue_pwm_output_7 Serial UDB Extra PWM Output Channel 7 - * @param sue_pwm_output_8 Serial UDB Extra PWM Output Channel 8 - * @param sue_pwm_output_9 Serial UDB Extra PWM Output Channel 9 - * @param sue_pwm_output_10 Serial UDB Extra PWM Output Channel 10 - * @param sue_imu_location_x Serial UDB Extra IMU Location X - * @param sue_imu_location_y Serial UDB Extra IMU Location Y - * @param sue_imu_location_z Serial UDB Extra IMU Location Z - * @param sue_flags Serial UDB Extra Status Flags - * @param sue_osc_fails Serial UDB Extra Oscillator Failure Count - * @param sue_imu_velocity_x Serial UDB Extra IMU Velocity X - * @param sue_imu_velocity_y Serial UDB Extra IMU Velocity Y - * @param sue_imu_velocity_z Serial UDB Extra IMU Velocity Z - * @param sue_waypoint_goal_x Serial UDB Extra Current Waypoint Goal X - * @param sue_waypoint_goal_y Serial UDB Extra Current Waypoint Goal Y - * @param sue_waypoint_goal_z Serial UDB Extra Current Waypoint Goal Z - * @param sue_memory_stack_free Serial UDB Extra Stack Memory Free - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f2_b_send(mavlink_channel_t chan, uint32_t sue_time, int16_t sue_pwm_input_1, int16_t sue_pwm_input_2, int16_t sue_pwm_input_3, int16_t sue_pwm_input_4, int16_t sue_pwm_input_5, int16_t sue_pwm_input_6, int16_t sue_pwm_input_7, int16_t sue_pwm_input_8, int16_t sue_pwm_input_9, int16_t sue_pwm_input_10, int16_t sue_pwm_output_1, int16_t sue_pwm_output_2, int16_t sue_pwm_output_3, int16_t sue_pwm_output_4, int16_t sue_pwm_output_5, int16_t sue_pwm_output_6, int16_t sue_pwm_output_7, int16_t sue_pwm_output_8, int16_t sue_pwm_output_9, int16_t sue_pwm_output_10, int16_t sue_imu_location_x, int16_t sue_imu_location_y, int16_t sue_imu_location_z, uint32_t sue_flags, int16_t sue_osc_fails, int16_t sue_imu_velocity_x, int16_t sue_imu_velocity_y, int16_t sue_imu_velocity_z, int16_t sue_waypoint_goal_x, int16_t sue_waypoint_goal_y, int16_t sue_waypoint_goal_z, int16_t sue_memory_stack_free) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN]; - _mav_put_uint32_t(buf, 0, sue_time); - _mav_put_uint32_t(buf, 4, sue_flags); - _mav_put_int16_t(buf, 8, sue_pwm_input_1); - _mav_put_int16_t(buf, 10, sue_pwm_input_2); - _mav_put_int16_t(buf, 12, sue_pwm_input_3); - _mav_put_int16_t(buf, 14, sue_pwm_input_4); - _mav_put_int16_t(buf, 16, sue_pwm_input_5); - _mav_put_int16_t(buf, 18, sue_pwm_input_6); - _mav_put_int16_t(buf, 20, sue_pwm_input_7); - _mav_put_int16_t(buf, 22, sue_pwm_input_8); - _mav_put_int16_t(buf, 24, sue_pwm_input_9); - _mav_put_int16_t(buf, 26, sue_pwm_input_10); - _mav_put_int16_t(buf, 28, sue_pwm_output_1); - _mav_put_int16_t(buf, 30, sue_pwm_output_2); - _mav_put_int16_t(buf, 32, sue_pwm_output_3); - _mav_put_int16_t(buf, 34, sue_pwm_output_4); - _mav_put_int16_t(buf, 36, sue_pwm_output_5); - _mav_put_int16_t(buf, 38, sue_pwm_output_6); - _mav_put_int16_t(buf, 40, sue_pwm_output_7); - _mav_put_int16_t(buf, 42, sue_pwm_output_8); - _mav_put_int16_t(buf, 44, sue_pwm_output_9); - _mav_put_int16_t(buf, 46, sue_pwm_output_10); - _mav_put_int16_t(buf, 48, sue_imu_location_x); - _mav_put_int16_t(buf, 50, sue_imu_location_y); - _mav_put_int16_t(buf, 52, sue_imu_location_z); - _mav_put_int16_t(buf, 54, sue_osc_fails); - _mav_put_int16_t(buf, 56, sue_imu_velocity_x); - _mav_put_int16_t(buf, 58, sue_imu_velocity_y); - _mav_put_int16_t(buf, 60, sue_imu_velocity_z); - _mav_put_int16_t(buf, 62, sue_waypoint_goal_x); - _mav_put_int16_t(buf, 64, sue_waypoint_goal_y); - _mav_put_int16_t(buf, 66, sue_waypoint_goal_z); - _mav_put_int16_t(buf, 68, sue_memory_stack_free); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#endif -#else - mavlink_serial_udb_extra_f2_b_t packet; - packet.sue_time = sue_time; - packet.sue_flags = sue_flags; - packet.sue_pwm_input_1 = sue_pwm_input_1; - packet.sue_pwm_input_2 = sue_pwm_input_2; - packet.sue_pwm_input_3 = sue_pwm_input_3; - packet.sue_pwm_input_4 = sue_pwm_input_4; - packet.sue_pwm_input_5 = sue_pwm_input_5; - packet.sue_pwm_input_6 = sue_pwm_input_6; - packet.sue_pwm_input_7 = sue_pwm_input_7; - packet.sue_pwm_input_8 = sue_pwm_input_8; - packet.sue_pwm_input_9 = sue_pwm_input_9; - packet.sue_pwm_input_10 = sue_pwm_input_10; - packet.sue_pwm_output_1 = sue_pwm_output_1; - packet.sue_pwm_output_2 = sue_pwm_output_2; - packet.sue_pwm_output_3 = sue_pwm_output_3; - packet.sue_pwm_output_4 = sue_pwm_output_4; - packet.sue_pwm_output_5 = sue_pwm_output_5; - packet.sue_pwm_output_6 = sue_pwm_output_6; - packet.sue_pwm_output_7 = sue_pwm_output_7; - packet.sue_pwm_output_8 = sue_pwm_output_8; - packet.sue_pwm_output_9 = sue_pwm_output_9; - packet.sue_pwm_output_10 = sue_pwm_output_10; - packet.sue_imu_location_x = sue_imu_location_x; - packet.sue_imu_location_y = sue_imu_location_y; - packet.sue_imu_location_z = sue_imu_location_z; - packet.sue_osc_fails = sue_osc_fails; - packet.sue_imu_velocity_x = sue_imu_velocity_x; - packet.sue_imu_velocity_y = sue_imu_velocity_y; - packet.sue_imu_velocity_z = sue_imu_velocity_z; - packet.sue_waypoint_goal_x = sue_waypoint_goal_x; - packet.sue_waypoint_goal_y = sue_waypoint_goal_y; - packet.sue_waypoint_goal_z = sue_waypoint_goal_z; - packet.sue_memory_stack_free = sue_memory_stack_free; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f2_b_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t sue_time, int16_t sue_pwm_input_1, int16_t sue_pwm_input_2, int16_t sue_pwm_input_3, int16_t sue_pwm_input_4, int16_t sue_pwm_input_5, int16_t sue_pwm_input_6, int16_t sue_pwm_input_7, int16_t sue_pwm_input_8, int16_t sue_pwm_input_9, int16_t sue_pwm_input_10, int16_t sue_pwm_output_1, int16_t sue_pwm_output_2, int16_t sue_pwm_output_3, int16_t sue_pwm_output_4, int16_t sue_pwm_output_5, int16_t sue_pwm_output_6, int16_t sue_pwm_output_7, int16_t sue_pwm_output_8, int16_t sue_pwm_output_9, int16_t sue_pwm_output_10, int16_t sue_imu_location_x, int16_t sue_imu_location_y, int16_t sue_imu_location_z, uint32_t sue_flags, int16_t sue_osc_fails, int16_t sue_imu_velocity_x, int16_t sue_imu_velocity_y, int16_t sue_imu_velocity_z, int16_t sue_waypoint_goal_x, int16_t sue_waypoint_goal_y, int16_t sue_waypoint_goal_z, int16_t sue_memory_stack_free) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint32_t(buf, 0, sue_time); - _mav_put_uint32_t(buf, 4, sue_flags); - _mav_put_int16_t(buf, 8, sue_pwm_input_1); - _mav_put_int16_t(buf, 10, sue_pwm_input_2); - _mav_put_int16_t(buf, 12, sue_pwm_input_3); - _mav_put_int16_t(buf, 14, sue_pwm_input_4); - _mav_put_int16_t(buf, 16, sue_pwm_input_5); - _mav_put_int16_t(buf, 18, sue_pwm_input_6); - _mav_put_int16_t(buf, 20, sue_pwm_input_7); - _mav_put_int16_t(buf, 22, sue_pwm_input_8); - _mav_put_int16_t(buf, 24, sue_pwm_input_9); - _mav_put_int16_t(buf, 26, sue_pwm_input_10); - _mav_put_int16_t(buf, 28, sue_pwm_output_1); - _mav_put_int16_t(buf, 30, sue_pwm_output_2); - _mav_put_int16_t(buf, 32, sue_pwm_output_3); - _mav_put_int16_t(buf, 34, sue_pwm_output_4); - _mav_put_int16_t(buf, 36, sue_pwm_output_5); - _mav_put_int16_t(buf, 38, sue_pwm_output_6); - _mav_put_int16_t(buf, 40, sue_pwm_output_7); - _mav_put_int16_t(buf, 42, sue_pwm_output_8); - _mav_put_int16_t(buf, 44, sue_pwm_output_9); - _mav_put_int16_t(buf, 46, sue_pwm_output_10); - _mav_put_int16_t(buf, 48, sue_imu_location_x); - _mav_put_int16_t(buf, 50, sue_imu_location_y); - _mav_put_int16_t(buf, 52, sue_imu_location_z); - _mav_put_int16_t(buf, 54, sue_osc_fails); - _mav_put_int16_t(buf, 56, sue_imu_velocity_x); - _mav_put_int16_t(buf, 58, sue_imu_velocity_y); - _mav_put_int16_t(buf, 60, sue_imu_velocity_z); - _mav_put_int16_t(buf, 62, sue_waypoint_goal_x); - _mav_put_int16_t(buf, 64, sue_waypoint_goal_y); - _mav_put_int16_t(buf, 66, sue_waypoint_goal_z); - _mav_put_int16_t(buf, 68, sue_memory_stack_free); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#endif -#else - mavlink_serial_udb_extra_f2_b_t *packet = (mavlink_serial_udb_extra_f2_b_t *)msgbuf; - packet->sue_time = sue_time; - packet->sue_flags = sue_flags; - packet->sue_pwm_input_1 = sue_pwm_input_1; - packet->sue_pwm_input_2 = sue_pwm_input_2; - packet->sue_pwm_input_3 = sue_pwm_input_3; - packet->sue_pwm_input_4 = sue_pwm_input_4; - packet->sue_pwm_input_5 = sue_pwm_input_5; - packet->sue_pwm_input_6 = sue_pwm_input_6; - packet->sue_pwm_input_7 = sue_pwm_input_7; - packet->sue_pwm_input_8 = sue_pwm_input_8; - packet->sue_pwm_input_9 = sue_pwm_input_9; - packet->sue_pwm_input_10 = sue_pwm_input_10; - packet->sue_pwm_output_1 = sue_pwm_output_1; - packet->sue_pwm_output_2 = sue_pwm_output_2; - packet->sue_pwm_output_3 = sue_pwm_output_3; - packet->sue_pwm_output_4 = sue_pwm_output_4; - packet->sue_pwm_output_5 = sue_pwm_output_5; - packet->sue_pwm_output_6 = sue_pwm_output_6; - packet->sue_pwm_output_7 = sue_pwm_output_7; - packet->sue_pwm_output_8 = sue_pwm_output_8; - packet->sue_pwm_output_9 = sue_pwm_output_9; - packet->sue_pwm_output_10 = sue_pwm_output_10; - packet->sue_imu_location_x = sue_imu_location_x; - packet->sue_imu_location_y = sue_imu_location_y; - packet->sue_imu_location_z = sue_imu_location_z; - packet->sue_osc_fails = sue_osc_fails; - packet->sue_imu_velocity_x = sue_imu_velocity_x; - packet->sue_imu_velocity_y = sue_imu_velocity_y; - packet->sue_imu_velocity_z = sue_imu_velocity_z; - packet->sue_waypoint_goal_x = sue_waypoint_goal_x; - packet->sue_waypoint_goal_y = sue_waypoint_goal_y; - packet->sue_waypoint_goal_z = sue_waypoint_goal_z; - packet->sue_memory_stack_free = sue_memory_stack_free; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F2_B UNPACKING - - -/** - * @brief Get field sue_time from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra Time - */ -static inline uint32_t mavlink_msg_serial_udb_extra_f2_b_get_sue_time(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 0); -} - -/** - * @brief Get field sue_pwm_input_1 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 1 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 8); -} - -/** - * @brief Get field sue_pwm_input_2 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 2 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 10); -} - -/** - * @brief Get field sue_pwm_input_3 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 3 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 12); -} - -/** - * @brief Get field sue_pwm_input_4 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 4 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field sue_pwm_input_5 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 5 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 16); -} - -/** - * @brief Get field sue_pwm_input_6 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 6 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 18); -} - -/** - * @brief Get field sue_pwm_input_7 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 7 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 20); -} - -/** - * @brief Get field sue_pwm_input_8 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 8 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 22); -} - -/** - * @brief Get field sue_pwm_input_9 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 9 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_9(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 24); -} - -/** - * @brief Get field sue_pwm_input_10 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Input Channel 10 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_10(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 26); -} - -/** - * @brief Get field sue_pwm_output_1 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 1 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 28); -} - -/** - * @brief Get field sue_pwm_output_2 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 2 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 30); -} - -/** - * @brief Get field sue_pwm_output_3 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 3 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 32); -} - -/** - * @brief Get field sue_pwm_output_4 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 4 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 34); -} - -/** - * @brief Get field sue_pwm_output_5 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 5 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_5(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 36); -} - -/** - * @brief Get field sue_pwm_output_6 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 6 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_6(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 38); -} - -/** - * @brief Get field sue_pwm_output_7 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 7 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_7(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 40); -} - -/** - * @brief Get field sue_pwm_output_8 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 8 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 42); -} - -/** - * @brief Get field sue_pwm_output_9 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 9 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_9(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 44); -} - -/** - * @brief Get field sue_pwm_output_10 from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra PWM Output Channel 10 - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_10(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 46); -} - -/** - * @brief Get field sue_imu_location_x from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra IMU Location X - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 48); -} - -/** - * @brief Get field sue_imu_location_y from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra IMU Location Y - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 50); -} - -/** - * @brief Get field sue_imu_location_z from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra IMU Location Z - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 52); -} - -/** - * @brief Get field sue_flags from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra Status Flags - */ -static inline uint32_t mavlink_msg_serial_udb_extra_f2_b_get_sue_flags(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 4); -} - -/** - * @brief Get field sue_osc_fails from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra Oscillator Failure Count - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_osc_fails(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 54); -} - -/** - * @brief Get field sue_imu_velocity_x from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra IMU Velocity X - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 56); -} - -/** - * @brief Get field sue_imu_velocity_y from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra IMU Velocity Y - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 58); -} - -/** - * @brief Get field sue_imu_velocity_z from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra IMU Velocity Z - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 60); -} - -/** - * @brief Get field sue_waypoint_goal_x from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra Current Waypoint Goal X - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 62); -} - -/** - * @brief Get field sue_waypoint_goal_y from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra Current Waypoint Goal Y - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 64); -} - -/** - * @brief Get field sue_waypoint_goal_z from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra Current Waypoint Goal Z - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 66); -} - -/** - * @brief Get field sue_memory_stack_free from serial_udb_extra_f2_b message - * - * @return Serial UDB Extra Stack Memory Free - */ -static inline int16_t mavlink_msg_serial_udb_extra_f2_b_get_sue_memory_stack_free(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 68); -} - -/** - * @brief Decode a serial_udb_extra_f2_b message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f2_b C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f2_b_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f2_b_t* serial_udb_extra_f2_b) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_udb_extra_f2_b->sue_time = mavlink_msg_serial_udb_extra_f2_b_get_sue_time(msg); - serial_udb_extra_f2_b->sue_flags = mavlink_msg_serial_udb_extra_f2_b_get_sue_flags(msg); - serial_udb_extra_f2_b->sue_pwm_input_1 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_1(msg); - serial_udb_extra_f2_b->sue_pwm_input_2 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_2(msg); - serial_udb_extra_f2_b->sue_pwm_input_3 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_3(msg); - serial_udb_extra_f2_b->sue_pwm_input_4 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_4(msg); - serial_udb_extra_f2_b->sue_pwm_input_5 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_5(msg); - serial_udb_extra_f2_b->sue_pwm_input_6 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_6(msg); - serial_udb_extra_f2_b->sue_pwm_input_7 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_7(msg); - serial_udb_extra_f2_b->sue_pwm_input_8 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_8(msg); - serial_udb_extra_f2_b->sue_pwm_input_9 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_9(msg); - serial_udb_extra_f2_b->sue_pwm_input_10 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_input_10(msg); - serial_udb_extra_f2_b->sue_pwm_output_1 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_1(msg); - serial_udb_extra_f2_b->sue_pwm_output_2 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_2(msg); - serial_udb_extra_f2_b->sue_pwm_output_3 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_3(msg); - serial_udb_extra_f2_b->sue_pwm_output_4 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_4(msg); - serial_udb_extra_f2_b->sue_pwm_output_5 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_5(msg); - serial_udb_extra_f2_b->sue_pwm_output_6 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_6(msg); - serial_udb_extra_f2_b->sue_pwm_output_7 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_7(msg); - serial_udb_extra_f2_b->sue_pwm_output_8 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_8(msg); - serial_udb_extra_f2_b->sue_pwm_output_9 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_9(msg); - serial_udb_extra_f2_b->sue_pwm_output_10 = mavlink_msg_serial_udb_extra_f2_b_get_sue_pwm_output_10(msg); - serial_udb_extra_f2_b->sue_imu_location_x = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_x(msg); - serial_udb_extra_f2_b->sue_imu_location_y = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_y(msg); - serial_udb_extra_f2_b->sue_imu_location_z = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_location_z(msg); - serial_udb_extra_f2_b->sue_osc_fails = mavlink_msg_serial_udb_extra_f2_b_get_sue_osc_fails(msg); - serial_udb_extra_f2_b->sue_imu_velocity_x = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_x(msg); - serial_udb_extra_f2_b->sue_imu_velocity_y = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_y(msg); - serial_udb_extra_f2_b->sue_imu_velocity_z = mavlink_msg_serial_udb_extra_f2_b_get_sue_imu_velocity_z(msg); - serial_udb_extra_f2_b->sue_waypoint_goal_x = mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_x(msg); - serial_udb_extra_f2_b->sue_waypoint_goal_y = mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_y(msg); - serial_udb_extra_f2_b->sue_waypoint_goal_z = mavlink_msg_serial_udb_extra_f2_b_get_sue_waypoint_goal_z(msg); - serial_udb_extra_f2_b->sue_memory_stack_free = mavlink_msg_serial_udb_extra_f2_b_get_sue_memory_stack_free(msg); -#else - memcpy(serial_udb_extra_f2_b, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F2_B_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h deleted file mode 100644 index edd1e924c..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f4.h +++ /dev/null @@ -1,425 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F4 PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4 172 - -typedef struct __mavlink_serial_udb_extra_f4_t -{ - uint8_t sue_ROLL_STABILIZATION_AILERONS; ///< Serial UDB Extra Roll Stabilization with Ailerons Enabled - uint8_t sue_ROLL_STABILIZATION_RUDDER; ///< Serial UDB Extra Roll Stabilization with Rudder Enabled - uint8_t sue_PITCH_STABILIZATION; ///< Serial UDB Extra Pitch Stabilization Enabled - uint8_t sue_YAW_STABILIZATION_RUDDER; ///< Serial UDB Extra Yaw Stabilization using Rudder Enabled - uint8_t sue_YAW_STABILIZATION_AILERON; ///< Serial UDB Extra Yaw Stabilization using Ailerons Enabled - uint8_t sue_AILERON_NAVIGATION; ///< Serial UDB Extra Navigation with Ailerons Enabled - uint8_t sue_RUDDER_NAVIGATION; ///< Serial UDB Extra Navigation with Rudder Enabled - uint8_t sue_ALTITUDEHOLD_STABILIZED; ///< Serial UDB Extra Type of Alitude Hold when in Stabilized Mode - uint8_t sue_ALTITUDEHOLD_WAYPOINT; ///< Serial UDB Extra Type of Alitude Hold when in Waypoint Mode - uint8_t sue_RACING_MODE; ///< Serial UDB Extra Firmware racing mode enabled -} mavlink_serial_udb_extra_f4_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN 10 -#define MAVLINK_MSG_ID_172_LEN 10 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC 191 -#define MAVLINK_MSG_ID_172_CRC 191 - - - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F4 { \ - "SERIAL_UDB_EXTRA_F4", \ - 10, \ - { { "sue_ROLL_STABILIZATION_AILERONS", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_serial_udb_extra_f4_t, sue_ROLL_STABILIZATION_AILERONS) }, \ - { "sue_ROLL_STABILIZATION_RUDDER", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_serial_udb_extra_f4_t, sue_ROLL_STABILIZATION_RUDDER) }, \ - { "sue_PITCH_STABILIZATION", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_serial_udb_extra_f4_t, sue_PITCH_STABILIZATION) }, \ - { "sue_YAW_STABILIZATION_RUDDER", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_serial_udb_extra_f4_t, sue_YAW_STABILIZATION_RUDDER) }, \ - { "sue_YAW_STABILIZATION_AILERON", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_serial_udb_extra_f4_t, sue_YAW_STABILIZATION_AILERON) }, \ - { "sue_AILERON_NAVIGATION", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_serial_udb_extra_f4_t, sue_AILERON_NAVIGATION) }, \ - { "sue_RUDDER_NAVIGATION", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_serial_udb_extra_f4_t, sue_RUDDER_NAVIGATION) }, \ - { "sue_ALTITUDEHOLD_STABILIZED", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_serial_udb_extra_f4_t, sue_ALTITUDEHOLD_STABILIZED) }, \ - { "sue_ALTITUDEHOLD_WAYPOINT", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_serial_udb_extra_f4_t, sue_ALTITUDEHOLD_WAYPOINT) }, \ - { "sue_RACING_MODE", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_serial_udb_extra_f4_t, sue_RACING_MODE) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f4 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_ROLL_STABILIZATION_AILERONS Serial UDB Extra Roll Stabilization with Ailerons Enabled - * @param sue_ROLL_STABILIZATION_RUDDER Serial UDB Extra Roll Stabilization with Rudder Enabled - * @param sue_PITCH_STABILIZATION Serial UDB Extra Pitch Stabilization Enabled - * @param sue_YAW_STABILIZATION_RUDDER Serial UDB Extra Yaw Stabilization using Rudder Enabled - * @param sue_YAW_STABILIZATION_AILERON Serial UDB Extra Yaw Stabilization using Ailerons Enabled - * @param sue_AILERON_NAVIGATION Serial UDB Extra Navigation with Ailerons Enabled - * @param sue_RUDDER_NAVIGATION Serial UDB Extra Navigation with Rudder Enabled - * @param sue_ALTITUDEHOLD_STABILIZED Serial UDB Extra Type of Alitude Hold when in Stabilized Mode - * @param sue_ALTITUDEHOLD_WAYPOINT Serial UDB Extra Type of Alitude Hold when in Waypoint Mode - * @param sue_RACING_MODE Serial UDB Extra Firmware racing mode enabled - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t sue_ROLL_STABILIZATION_AILERONS, uint8_t sue_ROLL_STABILIZATION_RUDDER, uint8_t sue_PITCH_STABILIZATION, uint8_t sue_YAW_STABILIZATION_RUDDER, uint8_t sue_YAW_STABILIZATION_AILERON, uint8_t sue_AILERON_NAVIGATION, uint8_t sue_RUDDER_NAVIGATION, uint8_t sue_ALTITUDEHOLD_STABILIZED, uint8_t sue_ALTITUDEHOLD_WAYPOINT, uint8_t sue_RACING_MODE) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN]; - _mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS); - _mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER); - _mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION); - _mav_put_uint8_t(buf, 3, sue_YAW_STABILIZATION_RUDDER); - _mav_put_uint8_t(buf, 4, sue_YAW_STABILIZATION_AILERON); - _mav_put_uint8_t(buf, 5, sue_AILERON_NAVIGATION); - _mav_put_uint8_t(buf, 6, sue_RUDDER_NAVIGATION); - _mav_put_uint8_t(buf, 7, sue_ALTITUDEHOLD_STABILIZED); - _mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT); - _mav_put_uint8_t(buf, 9, sue_RACING_MODE); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#else - mavlink_serial_udb_extra_f4_t packet; - packet.sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS; - packet.sue_ROLL_STABILIZATION_RUDDER = sue_ROLL_STABILIZATION_RUDDER; - packet.sue_PITCH_STABILIZATION = sue_PITCH_STABILIZATION; - packet.sue_YAW_STABILIZATION_RUDDER = sue_YAW_STABILIZATION_RUDDER; - packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; - packet.sue_AILERON_NAVIGATION = sue_AILERON_NAVIGATION; - packet.sue_RUDDER_NAVIGATION = sue_RUDDER_NAVIGATION; - packet.sue_ALTITUDEHOLD_STABILIZED = sue_ALTITUDEHOLD_STABILIZED; - packet.sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT; - packet.sue_RACING_MODE = sue_RACING_MODE; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f4 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_ROLL_STABILIZATION_AILERONS Serial UDB Extra Roll Stabilization with Ailerons Enabled - * @param sue_ROLL_STABILIZATION_RUDDER Serial UDB Extra Roll Stabilization with Rudder Enabled - * @param sue_PITCH_STABILIZATION Serial UDB Extra Pitch Stabilization Enabled - * @param sue_YAW_STABILIZATION_RUDDER Serial UDB Extra Yaw Stabilization using Rudder Enabled - * @param sue_YAW_STABILIZATION_AILERON Serial UDB Extra Yaw Stabilization using Ailerons Enabled - * @param sue_AILERON_NAVIGATION Serial UDB Extra Navigation with Ailerons Enabled - * @param sue_RUDDER_NAVIGATION Serial UDB Extra Navigation with Rudder Enabled - * @param sue_ALTITUDEHOLD_STABILIZED Serial UDB Extra Type of Alitude Hold when in Stabilized Mode - * @param sue_ALTITUDEHOLD_WAYPOINT Serial UDB Extra Type of Alitude Hold when in Waypoint Mode - * @param sue_RACING_MODE Serial UDB Extra Firmware racing mode enabled - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f4_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t sue_ROLL_STABILIZATION_AILERONS,uint8_t sue_ROLL_STABILIZATION_RUDDER,uint8_t sue_PITCH_STABILIZATION,uint8_t sue_YAW_STABILIZATION_RUDDER,uint8_t sue_YAW_STABILIZATION_AILERON,uint8_t sue_AILERON_NAVIGATION,uint8_t sue_RUDDER_NAVIGATION,uint8_t sue_ALTITUDEHOLD_STABILIZED,uint8_t sue_ALTITUDEHOLD_WAYPOINT,uint8_t sue_RACING_MODE) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN]; - _mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS); - _mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER); - _mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION); - _mav_put_uint8_t(buf, 3, sue_YAW_STABILIZATION_RUDDER); - _mav_put_uint8_t(buf, 4, sue_YAW_STABILIZATION_AILERON); - _mav_put_uint8_t(buf, 5, sue_AILERON_NAVIGATION); - _mav_put_uint8_t(buf, 6, sue_RUDDER_NAVIGATION); - _mav_put_uint8_t(buf, 7, sue_ALTITUDEHOLD_STABILIZED); - _mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT); - _mav_put_uint8_t(buf, 9, sue_RACING_MODE); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#else - mavlink_serial_udb_extra_f4_t packet; - packet.sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS; - packet.sue_ROLL_STABILIZATION_RUDDER = sue_ROLL_STABILIZATION_RUDDER; - packet.sue_PITCH_STABILIZATION = sue_PITCH_STABILIZATION; - packet.sue_YAW_STABILIZATION_RUDDER = sue_YAW_STABILIZATION_RUDDER; - packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; - packet.sue_AILERON_NAVIGATION = sue_AILERON_NAVIGATION; - packet.sue_RUDDER_NAVIGATION = sue_RUDDER_NAVIGATION; - packet.sue_ALTITUDEHOLD_STABILIZED = sue_ALTITUDEHOLD_STABILIZED; - packet.sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT; - packet.sue_RACING_MODE = sue_RACING_MODE; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f4 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f4 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f4_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f4_t* serial_udb_extra_f4) -{ - return mavlink_msg_serial_udb_extra_f4_pack(system_id, component_id, msg, serial_udb_extra_f4->sue_ROLL_STABILIZATION_AILERONS, serial_udb_extra_f4->sue_ROLL_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_PITCH_STABILIZATION, serial_udb_extra_f4->sue_YAW_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f4->sue_AILERON_NAVIGATION, serial_udb_extra_f4->sue_RUDDER_NAVIGATION, serial_udb_extra_f4->sue_ALTITUDEHOLD_STABILIZED, serial_udb_extra_f4->sue_ALTITUDEHOLD_WAYPOINT, serial_udb_extra_f4->sue_RACING_MODE); -} - -/** - * @brief Encode a serial_udb_extra_f4 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f4 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f4_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f4_t* serial_udb_extra_f4) -{ - return mavlink_msg_serial_udb_extra_f4_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f4->sue_ROLL_STABILIZATION_AILERONS, serial_udb_extra_f4->sue_ROLL_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_PITCH_STABILIZATION, serial_udb_extra_f4->sue_YAW_STABILIZATION_RUDDER, serial_udb_extra_f4->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f4->sue_AILERON_NAVIGATION, serial_udb_extra_f4->sue_RUDDER_NAVIGATION, serial_udb_extra_f4->sue_ALTITUDEHOLD_STABILIZED, serial_udb_extra_f4->sue_ALTITUDEHOLD_WAYPOINT, serial_udb_extra_f4->sue_RACING_MODE); -} - -/** - * @brief Send a serial_udb_extra_f4 message - * @param chan MAVLink channel to send the message - * - * @param sue_ROLL_STABILIZATION_AILERONS Serial UDB Extra Roll Stabilization with Ailerons Enabled - * @param sue_ROLL_STABILIZATION_RUDDER Serial UDB Extra Roll Stabilization with Rudder Enabled - * @param sue_PITCH_STABILIZATION Serial UDB Extra Pitch Stabilization Enabled - * @param sue_YAW_STABILIZATION_RUDDER Serial UDB Extra Yaw Stabilization using Rudder Enabled - * @param sue_YAW_STABILIZATION_AILERON Serial UDB Extra Yaw Stabilization using Ailerons Enabled - * @param sue_AILERON_NAVIGATION Serial UDB Extra Navigation with Ailerons Enabled - * @param sue_RUDDER_NAVIGATION Serial UDB Extra Navigation with Rudder Enabled - * @param sue_ALTITUDEHOLD_STABILIZED Serial UDB Extra Type of Alitude Hold when in Stabilized Mode - * @param sue_ALTITUDEHOLD_WAYPOINT Serial UDB Extra Type of Alitude Hold when in Waypoint Mode - * @param sue_RACING_MODE Serial UDB Extra Firmware racing mode enabled - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f4_send(mavlink_channel_t chan, uint8_t sue_ROLL_STABILIZATION_AILERONS, uint8_t sue_ROLL_STABILIZATION_RUDDER, uint8_t sue_PITCH_STABILIZATION, uint8_t sue_YAW_STABILIZATION_RUDDER, uint8_t sue_YAW_STABILIZATION_AILERON, uint8_t sue_AILERON_NAVIGATION, uint8_t sue_RUDDER_NAVIGATION, uint8_t sue_ALTITUDEHOLD_STABILIZED, uint8_t sue_ALTITUDEHOLD_WAYPOINT, uint8_t sue_RACING_MODE) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN]; - _mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS); - _mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER); - _mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION); - _mav_put_uint8_t(buf, 3, sue_YAW_STABILIZATION_RUDDER); - _mav_put_uint8_t(buf, 4, sue_YAW_STABILIZATION_AILERON); - _mav_put_uint8_t(buf, 5, sue_AILERON_NAVIGATION); - _mav_put_uint8_t(buf, 6, sue_RUDDER_NAVIGATION); - _mav_put_uint8_t(buf, 7, sue_ALTITUDEHOLD_STABILIZED); - _mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT); - _mav_put_uint8_t(buf, 9, sue_RACING_MODE); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#endif -#else - mavlink_serial_udb_extra_f4_t packet; - packet.sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS; - packet.sue_ROLL_STABILIZATION_RUDDER = sue_ROLL_STABILIZATION_RUDDER; - packet.sue_PITCH_STABILIZATION = sue_PITCH_STABILIZATION; - packet.sue_YAW_STABILIZATION_RUDDER = sue_YAW_STABILIZATION_RUDDER; - packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; - packet.sue_AILERON_NAVIGATION = sue_AILERON_NAVIGATION; - packet.sue_RUDDER_NAVIGATION = sue_RUDDER_NAVIGATION; - packet.sue_ALTITUDEHOLD_STABILIZED = sue_ALTITUDEHOLD_STABILIZED; - packet.sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT; - packet.sue_RACING_MODE = sue_RACING_MODE; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f4_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t sue_ROLL_STABILIZATION_AILERONS, uint8_t sue_ROLL_STABILIZATION_RUDDER, uint8_t sue_PITCH_STABILIZATION, uint8_t sue_YAW_STABILIZATION_RUDDER, uint8_t sue_YAW_STABILIZATION_AILERON, uint8_t sue_AILERON_NAVIGATION, uint8_t sue_RUDDER_NAVIGATION, uint8_t sue_ALTITUDEHOLD_STABILIZED, uint8_t sue_ALTITUDEHOLD_WAYPOINT, uint8_t sue_RACING_MODE) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, sue_ROLL_STABILIZATION_AILERONS); - _mav_put_uint8_t(buf, 1, sue_ROLL_STABILIZATION_RUDDER); - _mav_put_uint8_t(buf, 2, sue_PITCH_STABILIZATION); - _mav_put_uint8_t(buf, 3, sue_YAW_STABILIZATION_RUDDER); - _mav_put_uint8_t(buf, 4, sue_YAW_STABILIZATION_AILERON); - _mav_put_uint8_t(buf, 5, sue_AILERON_NAVIGATION); - _mav_put_uint8_t(buf, 6, sue_RUDDER_NAVIGATION); - _mav_put_uint8_t(buf, 7, sue_ALTITUDEHOLD_STABILIZED); - _mav_put_uint8_t(buf, 8, sue_ALTITUDEHOLD_WAYPOINT); - _mav_put_uint8_t(buf, 9, sue_RACING_MODE); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#endif -#else - mavlink_serial_udb_extra_f4_t *packet = (mavlink_serial_udb_extra_f4_t *)msgbuf; - packet->sue_ROLL_STABILIZATION_AILERONS = sue_ROLL_STABILIZATION_AILERONS; - packet->sue_ROLL_STABILIZATION_RUDDER = sue_ROLL_STABILIZATION_RUDDER; - packet->sue_PITCH_STABILIZATION = sue_PITCH_STABILIZATION; - packet->sue_YAW_STABILIZATION_RUDDER = sue_YAW_STABILIZATION_RUDDER; - packet->sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; - packet->sue_AILERON_NAVIGATION = sue_AILERON_NAVIGATION; - packet->sue_RUDDER_NAVIGATION = sue_RUDDER_NAVIGATION; - packet->sue_ALTITUDEHOLD_STABILIZED = sue_ALTITUDEHOLD_STABILIZED; - packet->sue_ALTITUDEHOLD_WAYPOINT = sue_ALTITUDEHOLD_WAYPOINT; - packet->sue_RACING_MODE = sue_RACING_MODE; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F4 UNPACKING - - -/** - * @brief Get field sue_ROLL_STABILIZATION_AILERONS from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Roll Stabilization with Ailerons Enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_ROLL_STABILIZATION_AILERONS(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field sue_ROLL_STABILIZATION_RUDDER from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Roll Stabilization with Rudder Enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_ROLL_STABILIZATION_RUDDER(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field sue_PITCH_STABILIZATION from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Pitch Stabilization Enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_PITCH_STABILIZATION(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field sue_YAW_STABILIZATION_RUDDER from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Yaw Stabilization using Rudder Enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_YAW_STABILIZATION_RUDDER(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Get field sue_YAW_STABILIZATION_AILERON from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Yaw Stabilization using Ailerons Enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_YAW_STABILIZATION_AILERON(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field sue_AILERON_NAVIGATION from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Navigation with Ailerons Enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_AILERON_NAVIGATION(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Get field sue_RUDDER_NAVIGATION from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Navigation with Rudder Enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_RUDDER_NAVIGATION(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 6); -} - -/** - * @brief Get field sue_ALTITUDEHOLD_STABILIZED from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Type of Alitude Hold when in Stabilized Mode - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_ALTITUDEHOLD_STABILIZED(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 7); -} - -/** - * @brief Get field sue_ALTITUDEHOLD_WAYPOINT from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Type of Alitude Hold when in Waypoint Mode - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_ALTITUDEHOLD_WAYPOINT(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field sue_RACING_MODE from serial_udb_extra_f4 message - * - * @return Serial UDB Extra Firmware racing mode enabled - */ -static inline uint8_t mavlink_msg_serial_udb_extra_f4_get_sue_RACING_MODE(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Decode a serial_udb_extra_f4 message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f4 C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f4_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f4_t* serial_udb_extra_f4) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_udb_extra_f4->sue_ROLL_STABILIZATION_AILERONS = mavlink_msg_serial_udb_extra_f4_get_sue_ROLL_STABILIZATION_AILERONS(msg); - serial_udb_extra_f4->sue_ROLL_STABILIZATION_RUDDER = mavlink_msg_serial_udb_extra_f4_get_sue_ROLL_STABILIZATION_RUDDER(msg); - serial_udb_extra_f4->sue_PITCH_STABILIZATION = mavlink_msg_serial_udb_extra_f4_get_sue_PITCH_STABILIZATION(msg); - serial_udb_extra_f4->sue_YAW_STABILIZATION_RUDDER = mavlink_msg_serial_udb_extra_f4_get_sue_YAW_STABILIZATION_RUDDER(msg); - serial_udb_extra_f4->sue_YAW_STABILIZATION_AILERON = mavlink_msg_serial_udb_extra_f4_get_sue_YAW_STABILIZATION_AILERON(msg); - serial_udb_extra_f4->sue_AILERON_NAVIGATION = mavlink_msg_serial_udb_extra_f4_get_sue_AILERON_NAVIGATION(msg); - serial_udb_extra_f4->sue_RUDDER_NAVIGATION = mavlink_msg_serial_udb_extra_f4_get_sue_RUDDER_NAVIGATION(msg); - serial_udb_extra_f4->sue_ALTITUDEHOLD_STABILIZED = mavlink_msg_serial_udb_extra_f4_get_sue_ALTITUDEHOLD_STABILIZED(msg); - serial_udb_extra_f4->sue_ALTITUDEHOLD_WAYPOINT = mavlink_msg_serial_udb_extra_f4_get_sue_ALTITUDEHOLD_WAYPOINT(msg); - serial_udb_extra_f4->sue_RACING_MODE = mavlink_msg_serial_udb_extra_f4_get_sue_RACING_MODE(msg); -#else - memcpy(serial_udb_extra_f4, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F4_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h deleted file mode 100644 index a821f65bb..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f5.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F5 PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5 173 - -typedef struct __mavlink_serial_udb_extra_f5_t -{ - float sue_YAWKP_AILERON; ///< Serial UDB YAWKP_AILERON Gain for Proporional control of navigation - float sue_YAWKD_AILERON; ///< Serial UDB YAWKD_AILERON Gain for Rate control of navigation - float sue_ROLLKP; ///< Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization - float sue_ROLLKD; ///< Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization - float sue_YAW_STABILIZATION_AILERON; ///< YAW_STABILIZATION_AILERON Proportional control - float sue_AILERON_BOOST; ///< Gain For Boosting Manual Aileron control When Plane Stabilized -} mavlink_serial_udb_extra_f5_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN 24 -#define MAVLINK_MSG_ID_173_LEN 24 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC 121 -#define MAVLINK_MSG_ID_173_CRC 121 - - - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F5 { \ - "SERIAL_UDB_EXTRA_F5", \ - 6, \ - { { "sue_YAWKP_AILERON", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_serial_udb_extra_f5_t, sue_YAWKP_AILERON) }, \ - { "sue_YAWKD_AILERON", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_serial_udb_extra_f5_t, sue_YAWKD_AILERON) }, \ - { "sue_ROLLKP", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_serial_udb_extra_f5_t, sue_ROLLKP) }, \ - { "sue_ROLLKD", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_serial_udb_extra_f5_t, sue_ROLLKD) }, \ - { "sue_YAW_STABILIZATION_AILERON", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_serial_udb_extra_f5_t, sue_YAW_STABILIZATION_AILERON) }, \ - { "sue_AILERON_BOOST", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_serial_udb_extra_f5_t, sue_AILERON_BOOST) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f5 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_YAWKP_AILERON Serial UDB YAWKP_AILERON Gain for Proporional control of navigation - * @param sue_YAWKD_AILERON Serial UDB YAWKD_AILERON Gain for Rate control of navigation - * @param sue_ROLLKP Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization - * @param sue_ROLLKD Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization - * @param sue_YAW_STABILIZATION_AILERON YAW_STABILIZATION_AILERON Proportional control - * @param sue_AILERON_BOOST Gain For Boosting Manual Aileron control When Plane Stabilized - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN]; - _mav_put_float(buf, 0, sue_YAWKP_AILERON); - _mav_put_float(buf, 4, sue_YAWKD_AILERON); - _mav_put_float(buf, 8, sue_ROLLKP); - _mav_put_float(buf, 12, sue_ROLLKD); - _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON); - _mav_put_float(buf, 20, sue_AILERON_BOOST); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#else - mavlink_serial_udb_extra_f5_t packet; - packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON; - packet.sue_YAWKD_AILERON = sue_YAWKD_AILERON; - packet.sue_ROLLKP = sue_ROLLKP; - packet.sue_ROLLKD = sue_ROLLKD; - packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; - packet.sue_AILERON_BOOST = sue_AILERON_BOOST; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f5 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_YAWKP_AILERON Serial UDB YAWKP_AILERON Gain for Proporional control of navigation - * @param sue_YAWKD_AILERON Serial UDB YAWKD_AILERON Gain for Rate control of navigation - * @param sue_ROLLKP Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization - * @param sue_ROLLKD Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization - * @param sue_YAW_STABILIZATION_AILERON YAW_STABILIZATION_AILERON Proportional control - * @param sue_AILERON_BOOST Gain For Boosting Manual Aileron control When Plane Stabilized - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f5_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float sue_YAWKP_AILERON,float sue_YAWKD_AILERON,float sue_ROLLKP,float sue_ROLLKD,float sue_YAW_STABILIZATION_AILERON,float sue_AILERON_BOOST) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN]; - _mav_put_float(buf, 0, sue_YAWKP_AILERON); - _mav_put_float(buf, 4, sue_YAWKD_AILERON); - _mav_put_float(buf, 8, sue_ROLLKP); - _mav_put_float(buf, 12, sue_ROLLKD); - _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON); - _mav_put_float(buf, 20, sue_AILERON_BOOST); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#else - mavlink_serial_udb_extra_f5_t packet; - packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON; - packet.sue_YAWKD_AILERON = sue_YAWKD_AILERON; - packet.sue_ROLLKP = sue_ROLLKP; - packet.sue_ROLLKD = sue_ROLLKD; - packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; - packet.sue_AILERON_BOOST = sue_AILERON_BOOST; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f5 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f5 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f5_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f5_t* serial_udb_extra_f5) -{ - return mavlink_msg_serial_udb_extra_f5_pack(system_id, component_id, msg, serial_udb_extra_f5->sue_YAWKP_AILERON, serial_udb_extra_f5->sue_YAWKD_AILERON, serial_udb_extra_f5->sue_ROLLKP, serial_udb_extra_f5->sue_ROLLKD, serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f5->sue_AILERON_BOOST); -} - -/** - * @brief Encode a serial_udb_extra_f5 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f5 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f5_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f5_t* serial_udb_extra_f5) -{ - return mavlink_msg_serial_udb_extra_f5_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f5->sue_YAWKP_AILERON, serial_udb_extra_f5->sue_YAWKD_AILERON, serial_udb_extra_f5->sue_ROLLKP, serial_udb_extra_f5->sue_ROLLKD, serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON, serial_udb_extra_f5->sue_AILERON_BOOST); -} - -/** - * @brief Send a serial_udb_extra_f5 message - * @param chan MAVLink channel to send the message - * - * @param sue_YAWKP_AILERON Serial UDB YAWKP_AILERON Gain for Proporional control of navigation - * @param sue_YAWKD_AILERON Serial UDB YAWKD_AILERON Gain for Rate control of navigation - * @param sue_ROLLKP Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization - * @param sue_ROLLKD Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization - * @param sue_YAW_STABILIZATION_AILERON YAW_STABILIZATION_AILERON Proportional control - * @param sue_AILERON_BOOST Gain For Boosting Manual Aileron control When Plane Stabilized - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f5_send(mavlink_channel_t chan, float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN]; - _mav_put_float(buf, 0, sue_YAWKP_AILERON); - _mav_put_float(buf, 4, sue_YAWKD_AILERON); - _mav_put_float(buf, 8, sue_ROLLKP); - _mav_put_float(buf, 12, sue_ROLLKD); - _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON); - _mav_put_float(buf, 20, sue_AILERON_BOOST); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#endif -#else - mavlink_serial_udb_extra_f5_t packet; - packet.sue_YAWKP_AILERON = sue_YAWKP_AILERON; - packet.sue_YAWKD_AILERON = sue_YAWKD_AILERON; - packet.sue_ROLLKP = sue_ROLLKP; - packet.sue_ROLLKD = sue_ROLLKD; - packet.sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; - packet.sue_AILERON_BOOST = sue_AILERON_BOOST; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f5_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float sue_YAWKP_AILERON, float sue_YAWKD_AILERON, float sue_ROLLKP, float sue_ROLLKD, float sue_YAW_STABILIZATION_AILERON, float sue_AILERON_BOOST) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, sue_YAWKP_AILERON); - _mav_put_float(buf, 4, sue_YAWKD_AILERON); - _mav_put_float(buf, 8, sue_ROLLKP); - _mav_put_float(buf, 12, sue_ROLLKD); - _mav_put_float(buf, 16, sue_YAW_STABILIZATION_AILERON); - _mav_put_float(buf, 20, sue_AILERON_BOOST); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#endif -#else - mavlink_serial_udb_extra_f5_t *packet = (mavlink_serial_udb_extra_f5_t *)msgbuf; - packet->sue_YAWKP_AILERON = sue_YAWKP_AILERON; - packet->sue_YAWKD_AILERON = sue_YAWKD_AILERON; - packet->sue_ROLLKP = sue_ROLLKP; - packet->sue_ROLLKD = sue_ROLLKD; - packet->sue_YAW_STABILIZATION_AILERON = sue_YAW_STABILIZATION_AILERON; - packet->sue_AILERON_BOOST = sue_AILERON_BOOST; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F5 UNPACKING - - -/** - * @brief Get field sue_YAWKP_AILERON from serial_udb_extra_f5 message - * - * @return Serial UDB YAWKP_AILERON Gain for Proporional control of navigation - */ -static inline float mavlink_msg_serial_udb_extra_f5_get_sue_YAWKP_AILERON(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field sue_YAWKD_AILERON from serial_udb_extra_f5 message - * - * @return Serial UDB YAWKD_AILERON Gain for Rate control of navigation - */ -static inline float mavlink_msg_serial_udb_extra_f5_get_sue_YAWKD_AILERON(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field sue_ROLLKP from serial_udb_extra_f5 message - * - * @return Serial UDB Extra ROLLKP Gain for Proportional control of roll stabilization - */ -static inline float mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKP(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field sue_ROLLKD from serial_udb_extra_f5 message - * - * @return Serial UDB Extra ROLLKD Gain for Rate control of roll stabilization - */ -static inline float mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKD(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field sue_YAW_STABILIZATION_AILERON from serial_udb_extra_f5 message - * - * @return YAW_STABILIZATION_AILERON Proportional control - */ -static inline float mavlink_msg_serial_udb_extra_f5_get_sue_YAW_STABILIZATION_AILERON(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field sue_AILERON_BOOST from serial_udb_extra_f5 message - * - * @return Gain For Boosting Manual Aileron control When Plane Stabilized - */ -static inline float mavlink_msg_serial_udb_extra_f5_get_sue_AILERON_BOOST(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a serial_udb_extra_f5 message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f5 C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f5_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f5_t* serial_udb_extra_f5) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_udb_extra_f5->sue_YAWKP_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAWKP_AILERON(msg); - serial_udb_extra_f5->sue_YAWKD_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAWKD_AILERON(msg); - serial_udb_extra_f5->sue_ROLLKP = mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKP(msg); - serial_udb_extra_f5->sue_ROLLKD = mavlink_msg_serial_udb_extra_f5_get_sue_ROLLKD(msg); - serial_udb_extra_f5->sue_YAW_STABILIZATION_AILERON = mavlink_msg_serial_udb_extra_f5_get_sue_YAW_STABILIZATION_AILERON(msg); - serial_udb_extra_f5->sue_AILERON_BOOST = mavlink_msg_serial_udb_extra_f5_get_sue_AILERON_BOOST(msg); -#else - memcpy(serial_udb_extra_f5, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F5_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h deleted file mode 100644 index 0eb24c986..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f6.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F6 PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6 174 - -typedef struct __mavlink_serial_udb_extra_f6_t -{ - float sue_PITCHGAIN; ///< Serial UDB Extra PITCHGAIN Proportional Control - float sue_PITCHKD; ///< Serial UDB Extra Pitch Rate Control - float sue_RUDDER_ELEV_MIX; ///< Serial UDB Extra Rudder to Elevator Mix - float sue_ROLL_ELEV_MIX; ///< Serial UDB Extra Roll to Elevator Mix - float sue_ELEVATOR_BOOST; ///< Gain For Boosting Manual Elevator control When Plane Stabilized -} mavlink_serial_udb_extra_f6_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN 20 -#define MAVLINK_MSG_ID_174_LEN 20 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC 54 -#define MAVLINK_MSG_ID_174_CRC 54 - - - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F6 { \ - "SERIAL_UDB_EXTRA_F6", \ - 5, \ - { { "sue_PITCHGAIN", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_serial_udb_extra_f6_t, sue_PITCHGAIN) }, \ - { "sue_PITCHKD", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_serial_udb_extra_f6_t, sue_PITCHKD) }, \ - { "sue_RUDDER_ELEV_MIX", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_serial_udb_extra_f6_t, sue_RUDDER_ELEV_MIX) }, \ - { "sue_ROLL_ELEV_MIX", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_serial_udb_extra_f6_t, sue_ROLL_ELEV_MIX) }, \ - { "sue_ELEVATOR_BOOST", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_serial_udb_extra_f6_t, sue_ELEVATOR_BOOST) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f6 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_PITCHGAIN Serial UDB Extra PITCHGAIN Proportional Control - * @param sue_PITCHKD Serial UDB Extra Pitch Rate Control - * @param sue_RUDDER_ELEV_MIX Serial UDB Extra Rudder to Elevator Mix - * @param sue_ROLL_ELEV_MIX Serial UDB Extra Roll to Elevator Mix - * @param sue_ELEVATOR_BOOST Gain For Boosting Manual Elevator control When Plane Stabilized - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float sue_PITCHGAIN, float sue_PITCHKD, float sue_RUDDER_ELEV_MIX, float sue_ROLL_ELEV_MIX, float sue_ELEVATOR_BOOST) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN]; - _mav_put_float(buf, 0, sue_PITCHGAIN); - _mav_put_float(buf, 4, sue_PITCHKD); - _mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX); - _mav_put_float(buf, 12, sue_ROLL_ELEV_MIX); - _mav_put_float(buf, 16, sue_ELEVATOR_BOOST); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#else - mavlink_serial_udb_extra_f6_t packet; - packet.sue_PITCHGAIN = sue_PITCHGAIN; - packet.sue_PITCHKD = sue_PITCHKD; - packet.sue_RUDDER_ELEV_MIX = sue_RUDDER_ELEV_MIX; - packet.sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX; - packet.sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f6 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_PITCHGAIN Serial UDB Extra PITCHGAIN Proportional Control - * @param sue_PITCHKD Serial UDB Extra Pitch Rate Control - * @param sue_RUDDER_ELEV_MIX Serial UDB Extra Rudder to Elevator Mix - * @param sue_ROLL_ELEV_MIX Serial UDB Extra Roll to Elevator Mix - * @param sue_ELEVATOR_BOOST Gain For Boosting Manual Elevator control When Plane Stabilized - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f6_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float sue_PITCHGAIN,float sue_PITCHKD,float sue_RUDDER_ELEV_MIX,float sue_ROLL_ELEV_MIX,float sue_ELEVATOR_BOOST) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN]; - _mav_put_float(buf, 0, sue_PITCHGAIN); - _mav_put_float(buf, 4, sue_PITCHKD); - _mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX); - _mav_put_float(buf, 12, sue_ROLL_ELEV_MIX); - _mav_put_float(buf, 16, sue_ELEVATOR_BOOST); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#else - mavlink_serial_udb_extra_f6_t packet; - packet.sue_PITCHGAIN = sue_PITCHGAIN; - packet.sue_PITCHKD = sue_PITCHKD; - packet.sue_RUDDER_ELEV_MIX = sue_RUDDER_ELEV_MIX; - packet.sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX; - packet.sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f6 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f6 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f6_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f6_t* serial_udb_extra_f6) -{ - return mavlink_msg_serial_udb_extra_f6_pack(system_id, component_id, msg, serial_udb_extra_f6->sue_PITCHGAIN, serial_udb_extra_f6->sue_PITCHKD, serial_udb_extra_f6->sue_RUDDER_ELEV_MIX, serial_udb_extra_f6->sue_ROLL_ELEV_MIX, serial_udb_extra_f6->sue_ELEVATOR_BOOST); -} - -/** - * @brief Encode a serial_udb_extra_f6 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f6 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f6_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f6_t* serial_udb_extra_f6) -{ - return mavlink_msg_serial_udb_extra_f6_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f6->sue_PITCHGAIN, serial_udb_extra_f6->sue_PITCHKD, serial_udb_extra_f6->sue_RUDDER_ELEV_MIX, serial_udb_extra_f6->sue_ROLL_ELEV_MIX, serial_udb_extra_f6->sue_ELEVATOR_BOOST); -} - -/** - * @brief Send a serial_udb_extra_f6 message - * @param chan MAVLink channel to send the message - * - * @param sue_PITCHGAIN Serial UDB Extra PITCHGAIN Proportional Control - * @param sue_PITCHKD Serial UDB Extra Pitch Rate Control - * @param sue_RUDDER_ELEV_MIX Serial UDB Extra Rudder to Elevator Mix - * @param sue_ROLL_ELEV_MIX Serial UDB Extra Roll to Elevator Mix - * @param sue_ELEVATOR_BOOST Gain For Boosting Manual Elevator control When Plane Stabilized - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f6_send(mavlink_channel_t chan, float sue_PITCHGAIN, float sue_PITCHKD, float sue_RUDDER_ELEV_MIX, float sue_ROLL_ELEV_MIX, float sue_ELEVATOR_BOOST) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN]; - _mav_put_float(buf, 0, sue_PITCHGAIN); - _mav_put_float(buf, 4, sue_PITCHKD); - _mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX); - _mav_put_float(buf, 12, sue_ROLL_ELEV_MIX); - _mav_put_float(buf, 16, sue_ELEVATOR_BOOST); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#endif -#else - mavlink_serial_udb_extra_f6_t packet; - packet.sue_PITCHGAIN = sue_PITCHGAIN; - packet.sue_PITCHKD = sue_PITCHKD; - packet.sue_RUDDER_ELEV_MIX = sue_RUDDER_ELEV_MIX; - packet.sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX; - packet.sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f6_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float sue_PITCHGAIN, float sue_PITCHKD, float sue_RUDDER_ELEV_MIX, float sue_ROLL_ELEV_MIX, float sue_ELEVATOR_BOOST) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, sue_PITCHGAIN); - _mav_put_float(buf, 4, sue_PITCHKD); - _mav_put_float(buf, 8, sue_RUDDER_ELEV_MIX); - _mav_put_float(buf, 12, sue_ROLL_ELEV_MIX); - _mav_put_float(buf, 16, sue_ELEVATOR_BOOST); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#endif -#else - mavlink_serial_udb_extra_f6_t *packet = (mavlink_serial_udb_extra_f6_t *)msgbuf; - packet->sue_PITCHGAIN = sue_PITCHGAIN; - packet->sue_PITCHKD = sue_PITCHKD; - packet->sue_RUDDER_ELEV_MIX = sue_RUDDER_ELEV_MIX; - packet->sue_ROLL_ELEV_MIX = sue_ROLL_ELEV_MIX; - packet->sue_ELEVATOR_BOOST = sue_ELEVATOR_BOOST; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F6 UNPACKING - - -/** - * @brief Get field sue_PITCHGAIN from serial_udb_extra_f6 message - * - * @return Serial UDB Extra PITCHGAIN Proportional Control - */ -static inline float mavlink_msg_serial_udb_extra_f6_get_sue_PITCHGAIN(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field sue_PITCHKD from serial_udb_extra_f6 message - * - * @return Serial UDB Extra Pitch Rate Control - */ -static inline float mavlink_msg_serial_udb_extra_f6_get_sue_PITCHKD(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field sue_RUDDER_ELEV_MIX from serial_udb_extra_f6 message - * - * @return Serial UDB Extra Rudder to Elevator Mix - */ -static inline float mavlink_msg_serial_udb_extra_f6_get_sue_RUDDER_ELEV_MIX(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field sue_ROLL_ELEV_MIX from serial_udb_extra_f6 message - * - * @return Serial UDB Extra Roll to Elevator Mix - */ -static inline float mavlink_msg_serial_udb_extra_f6_get_sue_ROLL_ELEV_MIX(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field sue_ELEVATOR_BOOST from serial_udb_extra_f6 message - * - * @return Gain For Boosting Manual Elevator control When Plane Stabilized - */ -static inline float mavlink_msg_serial_udb_extra_f6_get_sue_ELEVATOR_BOOST(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Decode a serial_udb_extra_f6 message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f6 C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f6_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f6_t* serial_udb_extra_f6) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_udb_extra_f6->sue_PITCHGAIN = mavlink_msg_serial_udb_extra_f6_get_sue_PITCHGAIN(msg); - serial_udb_extra_f6->sue_PITCHKD = mavlink_msg_serial_udb_extra_f6_get_sue_PITCHKD(msg); - serial_udb_extra_f6->sue_RUDDER_ELEV_MIX = mavlink_msg_serial_udb_extra_f6_get_sue_RUDDER_ELEV_MIX(msg); - serial_udb_extra_f6->sue_ROLL_ELEV_MIX = mavlink_msg_serial_udb_extra_f6_get_sue_ROLL_ELEV_MIX(msg); - serial_udb_extra_f6->sue_ELEVATOR_BOOST = mavlink_msg_serial_udb_extra_f6_get_sue_ELEVATOR_BOOST(msg); -#else - memcpy(serial_udb_extra_f6, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F6_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h deleted file mode 100644 index 58de7d01c..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f7.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F7 PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7 175 - -typedef struct __mavlink_serial_udb_extra_f7_t -{ - float sue_YAWKP_RUDDER; ///< Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation - float sue_YAWKD_RUDDER; ///< Serial UDB YAWKD_RUDDER Gain for Rate control of navigation - float sue_ROLLKP_RUDDER; ///< Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization - float sue_ROLLKD_RUDDER; ///< Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization - float sue_RUDDER_BOOST; ///< SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized - float sue_RTL_PITCH_DOWN; ///< Serial UDB Extra Return To Landing - Angle to Pitch Plane Down -} mavlink_serial_udb_extra_f7_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN 24 -#define MAVLINK_MSG_ID_175_LEN 24 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC 171 -#define MAVLINK_MSG_ID_175_CRC 171 - - - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F7 { \ - "SERIAL_UDB_EXTRA_F7", \ - 6, \ - { { "sue_YAWKP_RUDDER", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_serial_udb_extra_f7_t, sue_YAWKP_RUDDER) }, \ - { "sue_YAWKD_RUDDER", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_serial_udb_extra_f7_t, sue_YAWKD_RUDDER) }, \ - { "sue_ROLLKP_RUDDER", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_serial_udb_extra_f7_t, sue_ROLLKP_RUDDER) }, \ - { "sue_ROLLKD_RUDDER", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_serial_udb_extra_f7_t, sue_ROLLKD_RUDDER) }, \ - { "sue_RUDDER_BOOST", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_serial_udb_extra_f7_t, sue_RUDDER_BOOST) }, \ - { "sue_RTL_PITCH_DOWN", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_serial_udb_extra_f7_t, sue_RTL_PITCH_DOWN) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f7 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_YAWKP_RUDDER Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation - * @param sue_YAWKD_RUDDER Serial UDB YAWKD_RUDDER Gain for Rate control of navigation - * @param sue_ROLLKP_RUDDER Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization - * @param sue_ROLLKD_RUDDER Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization - * @param sue_RUDDER_BOOST SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized - * @param sue_RTL_PITCH_DOWN Serial UDB Extra Return To Landing - Angle to Pitch Plane Down - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float sue_YAWKP_RUDDER, float sue_YAWKD_RUDDER, float sue_ROLLKP_RUDDER, float sue_ROLLKD_RUDDER, float sue_RUDDER_BOOST, float sue_RTL_PITCH_DOWN) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN]; - _mav_put_float(buf, 0, sue_YAWKP_RUDDER); - _mav_put_float(buf, 4, sue_YAWKD_RUDDER); - _mav_put_float(buf, 8, sue_ROLLKP_RUDDER); - _mav_put_float(buf, 12, sue_ROLLKD_RUDDER); - _mav_put_float(buf, 16, sue_RUDDER_BOOST); - _mav_put_float(buf, 20, sue_RTL_PITCH_DOWN); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#else - mavlink_serial_udb_extra_f7_t packet; - packet.sue_YAWKP_RUDDER = sue_YAWKP_RUDDER; - packet.sue_YAWKD_RUDDER = sue_YAWKD_RUDDER; - packet.sue_ROLLKP_RUDDER = sue_ROLLKP_RUDDER; - packet.sue_ROLLKD_RUDDER = sue_ROLLKD_RUDDER; - packet.sue_RUDDER_BOOST = sue_RUDDER_BOOST; - packet.sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f7 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_YAWKP_RUDDER Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation - * @param sue_YAWKD_RUDDER Serial UDB YAWKD_RUDDER Gain for Rate control of navigation - * @param sue_ROLLKP_RUDDER Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization - * @param sue_ROLLKD_RUDDER Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization - * @param sue_RUDDER_BOOST SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized - * @param sue_RTL_PITCH_DOWN Serial UDB Extra Return To Landing - Angle to Pitch Plane Down - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f7_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float sue_YAWKP_RUDDER,float sue_YAWKD_RUDDER,float sue_ROLLKP_RUDDER,float sue_ROLLKD_RUDDER,float sue_RUDDER_BOOST,float sue_RTL_PITCH_DOWN) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN]; - _mav_put_float(buf, 0, sue_YAWKP_RUDDER); - _mav_put_float(buf, 4, sue_YAWKD_RUDDER); - _mav_put_float(buf, 8, sue_ROLLKP_RUDDER); - _mav_put_float(buf, 12, sue_ROLLKD_RUDDER); - _mav_put_float(buf, 16, sue_RUDDER_BOOST); - _mav_put_float(buf, 20, sue_RTL_PITCH_DOWN); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#else - mavlink_serial_udb_extra_f7_t packet; - packet.sue_YAWKP_RUDDER = sue_YAWKP_RUDDER; - packet.sue_YAWKD_RUDDER = sue_YAWKD_RUDDER; - packet.sue_ROLLKP_RUDDER = sue_ROLLKP_RUDDER; - packet.sue_ROLLKD_RUDDER = sue_ROLLKD_RUDDER; - packet.sue_RUDDER_BOOST = sue_RUDDER_BOOST; - packet.sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f7 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f7 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f7_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f7_t* serial_udb_extra_f7) -{ - return mavlink_msg_serial_udb_extra_f7_pack(system_id, component_id, msg, serial_udb_extra_f7->sue_YAWKP_RUDDER, serial_udb_extra_f7->sue_YAWKD_RUDDER, serial_udb_extra_f7->sue_ROLLKP_RUDDER, serial_udb_extra_f7->sue_ROLLKD_RUDDER, serial_udb_extra_f7->sue_RUDDER_BOOST, serial_udb_extra_f7->sue_RTL_PITCH_DOWN); -} - -/** - * @brief Encode a serial_udb_extra_f7 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f7 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f7_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f7_t* serial_udb_extra_f7) -{ - return mavlink_msg_serial_udb_extra_f7_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f7->sue_YAWKP_RUDDER, serial_udb_extra_f7->sue_YAWKD_RUDDER, serial_udb_extra_f7->sue_ROLLKP_RUDDER, serial_udb_extra_f7->sue_ROLLKD_RUDDER, serial_udb_extra_f7->sue_RUDDER_BOOST, serial_udb_extra_f7->sue_RTL_PITCH_DOWN); -} - -/** - * @brief Send a serial_udb_extra_f7 message - * @param chan MAVLink channel to send the message - * - * @param sue_YAWKP_RUDDER Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation - * @param sue_YAWKD_RUDDER Serial UDB YAWKD_RUDDER Gain for Rate control of navigation - * @param sue_ROLLKP_RUDDER Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization - * @param sue_ROLLKD_RUDDER Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization - * @param sue_RUDDER_BOOST SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized - * @param sue_RTL_PITCH_DOWN Serial UDB Extra Return To Landing - Angle to Pitch Plane Down - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f7_send(mavlink_channel_t chan, float sue_YAWKP_RUDDER, float sue_YAWKD_RUDDER, float sue_ROLLKP_RUDDER, float sue_ROLLKD_RUDDER, float sue_RUDDER_BOOST, float sue_RTL_PITCH_DOWN) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN]; - _mav_put_float(buf, 0, sue_YAWKP_RUDDER); - _mav_put_float(buf, 4, sue_YAWKD_RUDDER); - _mav_put_float(buf, 8, sue_ROLLKP_RUDDER); - _mav_put_float(buf, 12, sue_ROLLKD_RUDDER); - _mav_put_float(buf, 16, sue_RUDDER_BOOST); - _mav_put_float(buf, 20, sue_RTL_PITCH_DOWN); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#endif -#else - mavlink_serial_udb_extra_f7_t packet; - packet.sue_YAWKP_RUDDER = sue_YAWKP_RUDDER; - packet.sue_YAWKD_RUDDER = sue_YAWKD_RUDDER; - packet.sue_ROLLKP_RUDDER = sue_ROLLKP_RUDDER; - packet.sue_ROLLKD_RUDDER = sue_ROLLKD_RUDDER; - packet.sue_RUDDER_BOOST = sue_RUDDER_BOOST; - packet.sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f7_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float sue_YAWKP_RUDDER, float sue_YAWKD_RUDDER, float sue_ROLLKP_RUDDER, float sue_ROLLKD_RUDDER, float sue_RUDDER_BOOST, float sue_RTL_PITCH_DOWN) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, sue_YAWKP_RUDDER); - _mav_put_float(buf, 4, sue_YAWKD_RUDDER); - _mav_put_float(buf, 8, sue_ROLLKP_RUDDER); - _mav_put_float(buf, 12, sue_ROLLKD_RUDDER); - _mav_put_float(buf, 16, sue_RUDDER_BOOST); - _mav_put_float(buf, 20, sue_RTL_PITCH_DOWN); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#endif -#else - mavlink_serial_udb_extra_f7_t *packet = (mavlink_serial_udb_extra_f7_t *)msgbuf; - packet->sue_YAWKP_RUDDER = sue_YAWKP_RUDDER; - packet->sue_YAWKD_RUDDER = sue_YAWKD_RUDDER; - packet->sue_ROLLKP_RUDDER = sue_ROLLKP_RUDDER; - packet->sue_ROLLKD_RUDDER = sue_ROLLKD_RUDDER; - packet->sue_RUDDER_BOOST = sue_RUDDER_BOOST; - packet->sue_RTL_PITCH_DOWN = sue_RTL_PITCH_DOWN; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F7 UNPACKING - - -/** - * @brief Get field sue_YAWKP_RUDDER from serial_udb_extra_f7 message - * - * @return Serial UDB YAWKP_RUDDER Gain for Proporional control of navigation - */ -static inline float mavlink_msg_serial_udb_extra_f7_get_sue_YAWKP_RUDDER(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field sue_YAWKD_RUDDER from serial_udb_extra_f7 message - * - * @return Serial UDB YAWKD_RUDDER Gain for Rate control of navigation - */ -static inline float mavlink_msg_serial_udb_extra_f7_get_sue_YAWKD_RUDDER(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field sue_ROLLKP_RUDDER from serial_udb_extra_f7 message - * - * @return Serial UDB Extra ROLLKP_RUDDER Gain for Proportional control of roll stabilization - */ -static inline float mavlink_msg_serial_udb_extra_f7_get_sue_ROLLKP_RUDDER(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field sue_ROLLKD_RUDDER from serial_udb_extra_f7 message - * - * @return Serial UDB Extra ROLLKD_RUDDER Gain for Rate control of roll stabilization - */ -static inline float mavlink_msg_serial_udb_extra_f7_get_sue_ROLLKD_RUDDER(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field sue_RUDDER_BOOST from serial_udb_extra_f7 message - * - * @return SERIAL UDB EXTRA Rudder Boost Gain to Manual Control when stabilized - */ -static inline float mavlink_msg_serial_udb_extra_f7_get_sue_RUDDER_BOOST(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field sue_RTL_PITCH_DOWN from serial_udb_extra_f7 message - * - * @return Serial UDB Extra Return To Landing - Angle to Pitch Plane Down - */ -static inline float mavlink_msg_serial_udb_extra_f7_get_sue_RTL_PITCH_DOWN(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a serial_udb_extra_f7 message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f7 C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f7_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f7_t* serial_udb_extra_f7) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_udb_extra_f7->sue_YAWKP_RUDDER = mavlink_msg_serial_udb_extra_f7_get_sue_YAWKP_RUDDER(msg); - serial_udb_extra_f7->sue_YAWKD_RUDDER = mavlink_msg_serial_udb_extra_f7_get_sue_YAWKD_RUDDER(msg); - serial_udb_extra_f7->sue_ROLLKP_RUDDER = mavlink_msg_serial_udb_extra_f7_get_sue_ROLLKP_RUDDER(msg); - serial_udb_extra_f7->sue_ROLLKD_RUDDER = mavlink_msg_serial_udb_extra_f7_get_sue_ROLLKD_RUDDER(msg); - serial_udb_extra_f7->sue_RUDDER_BOOST = mavlink_msg_serial_udb_extra_f7_get_sue_RUDDER_BOOST(msg); - serial_udb_extra_f7->sue_RTL_PITCH_DOWN = mavlink_msg_serial_udb_extra_f7_get_sue_RTL_PITCH_DOWN(msg); -#else - memcpy(serial_udb_extra_f7, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F7_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h b/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h deleted file mode 100644 index 5cab81655..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/mavlink_msg_serial_udb_extra_f8.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE SERIAL_UDB_EXTRA_F8 PACKING - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8 176 - -typedef struct __mavlink_serial_udb_extra_f8_t -{ - float sue_HEIGHT_TARGET_MAX; ///< Serial UDB Extra HEIGHT_TARGET_MAX - float sue_HEIGHT_TARGET_MIN; ///< Serial UDB Extra HEIGHT_TARGET_MIN - float sue_ALT_HOLD_THROTTLE_MIN; ///< Serial UDB Extra ALT_HOLD_THROTTLE_MIN - float sue_ALT_HOLD_THROTTLE_MAX; ///< Serial UDB Extra ALT_HOLD_THROTTLE_MAX - float sue_ALT_HOLD_PITCH_MIN; ///< Serial UDB Extra ALT_HOLD_PITCH_MIN - float sue_ALT_HOLD_PITCH_MAX; ///< Serial UDB Extra ALT_HOLD_PITCH_MAX - float sue_ALT_HOLD_PITCH_HIGH; ///< Serial UDB Extra ALT_HOLD_PITCH_HIGH -} mavlink_serial_udb_extra_f8_t; - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN 28 -#define MAVLINK_MSG_ID_176_LEN 28 - -#define MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC 142 -#define MAVLINK_MSG_ID_176_CRC 142 - - - -#define MAVLINK_MESSAGE_INFO_SERIAL_UDB_EXTRA_F8 { \ - "SERIAL_UDB_EXTRA_F8", \ - 7, \ - { { "sue_HEIGHT_TARGET_MAX", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_serial_udb_extra_f8_t, sue_HEIGHT_TARGET_MAX) }, \ - { "sue_HEIGHT_TARGET_MIN", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_serial_udb_extra_f8_t, sue_HEIGHT_TARGET_MIN) }, \ - { "sue_ALT_HOLD_THROTTLE_MIN", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_THROTTLE_MIN) }, \ - { "sue_ALT_HOLD_THROTTLE_MAX", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_THROTTLE_MAX) }, \ - { "sue_ALT_HOLD_PITCH_MIN", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_PITCH_MIN) }, \ - { "sue_ALT_HOLD_PITCH_MAX", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_PITCH_MAX) }, \ - { "sue_ALT_HOLD_PITCH_HIGH", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_serial_udb_extra_f8_t, sue_ALT_HOLD_PITCH_HIGH) }, \ - } \ -} - - -/** - * @brief Pack a serial_udb_extra_f8 message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param sue_HEIGHT_TARGET_MAX Serial UDB Extra HEIGHT_TARGET_MAX - * @param sue_HEIGHT_TARGET_MIN Serial UDB Extra HEIGHT_TARGET_MIN - * @param sue_ALT_HOLD_THROTTLE_MIN Serial UDB Extra ALT_HOLD_THROTTLE_MIN - * @param sue_ALT_HOLD_THROTTLE_MAX Serial UDB Extra ALT_HOLD_THROTTLE_MAX - * @param sue_ALT_HOLD_PITCH_MIN Serial UDB Extra ALT_HOLD_PITCH_MIN - * @param sue_ALT_HOLD_PITCH_MAX Serial UDB Extra ALT_HOLD_PITCH_MAX - * @param sue_ALT_HOLD_PITCH_HIGH Serial UDB Extra ALT_HOLD_PITCH_HIGH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float sue_HEIGHT_TARGET_MAX, float sue_HEIGHT_TARGET_MIN, float sue_ALT_HOLD_THROTTLE_MIN, float sue_ALT_HOLD_THROTTLE_MAX, float sue_ALT_HOLD_PITCH_MIN, float sue_ALT_HOLD_PITCH_MAX, float sue_ALT_HOLD_PITCH_HIGH) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN]; - _mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX); - _mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN); - _mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN); - _mav_put_float(buf, 12, sue_ALT_HOLD_THROTTLE_MAX); - _mav_put_float(buf, 16, sue_ALT_HOLD_PITCH_MIN); - _mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX); - _mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#else - mavlink_serial_udb_extra_f8_t packet; - packet.sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX; - packet.sue_HEIGHT_TARGET_MIN = sue_HEIGHT_TARGET_MIN; - packet.sue_ALT_HOLD_THROTTLE_MIN = sue_ALT_HOLD_THROTTLE_MIN; - packet.sue_ALT_HOLD_THROTTLE_MAX = sue_ALT_HOLD_THROTTLE_MAX; - packet.sue_ALT_HOLD_PITCH_MIN = sue_ALT_HOLD_PITCH_MIN; - packet.sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX; - packet.sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#endif -} - -/** - * @brief Pack a serial_udb_extra_f8 message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sue_HEIGHT_TARGET_MAX Serial UDB Extra HEIGHT_TARGET_MAX - * @param sue_HEIGHT_TARGET_MIN Serial UDB Extra HEIGHT_TARGET_MIN - * @param sue_ALT_HOLD_THROTTLE_MIN Serial UDB Extra ALT_HOLD_THROTTLE_MIN - * @param sue_ALT_HOLD_THROTTLE_MAX Serial UDB Extra ALT_HOLD_THROTTLE_MAX - * @param sue_ALT_HOLD_PITCH_MIN Serial UDB Extra ALT_HOLD_PITCH_MIN - * @param sue_ALT_HOLD_PITCH_MAX Serial UDB Extra ALT_HOLD_PITCH_MAX - * @param sue_ALT_HOLD_PITCH_HIGH Serial UDB Extra ALT_HOLD_PITCH_HIGH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f8_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float sue_HEIGHT_TARGET_MAX,float sue_HEIGHT_TARGET_MIN,float sue_ALT_HOLD_THROTTLE_MIN,float sue_ALT_HOLD_THROTTLE_MAX,float sue_ALT_HOLD_PITCH_MIN,float sue_ALT_HOLD_PITCH_MAX,float sue_ALT_HOLD_PITCH_HIGH) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN]; - _mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX); - _mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN); - _mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN); - _mav_put_float(buf, 12, sue_ALT_HOLD_THROTTLE_MAX); - _mav_put_float(buf, 16, sue_ALT_HOLD_PITCH_MIN); - _mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX); - _mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#else - mavlink_serial_udb_extra_f8_t packet; - packet.sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX; - packet.sue_HEIGHT_TARGET_MIN = sue_HEIGHT_TARGET_MIN; - packet.sue_ALT_HOLD_THROTTLE_MIN = sue_ALT_HOLD_THROTTLE_MIN; - packet.sue_ALT_HOLD_THROTTLE_MAX = sue_ALT_HOLD_THROTTLE_MAX; - packet.sue_ALT_HOLD_PITCH_MIN = sue_ALT_HOLD_PITCH_MIN; - packet.sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX; - packet.sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#endif -} - -/** - * @brief Encode a serial_udb_extra_f8 struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f8 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f8_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_serial_udb_extra_f8_t* serial_udb_extra_f8) -{ - return mavlink_msg_serial_udb_extra_f8_pack(system_id, component_id, msg, serial_udb_extra_f8->sue_HEIGHT_TARGET_MAX, serial_udb_extra_f8->sue_HEIGHT_TARGET_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MIN, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_HIGH); -} - -/** - * @brief Encode a serial_udb_extra_f8 struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param serial_udb_extra_f8 C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_serial_udb_extra_f8_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_serial_udb_extra_f8_t* serial_udb_extra_f8) -{ - return mavlink_msg_serial_udb_extra_f8_pack_chan(system_id, component_id, chan, msg, serial_udb_extra_f8->sue_HEIGHT_TARGET_MAX, serial_udb_extra_f8->sue_HEIGHT_TARGET_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MIN, serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MIN, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MAX, serial_udb_extra_f8->sue_ALT_HOLD_PITCH_HIGH); -} - -/** - * @brief Send a serial_udb_extra_f8 message - * @param chan MAVLink channel to send the message - * - * @param sue_HEIGHT_TARGET_MAX Serial UDB Extra HEIGHT_TARGET_MAX - * @param sue_HEIGHT_TARGET_MIN Serial UDB Extra HEIGHT_TARGET_MIN - * @param sue_ALT_HOLD_THROTTLE_MIN Serial UDB Extra ALT_HOLD_THROTTLE_MIN - * @param sue_ALT_HOLD_THROTTLE_MAX Serial UDB Extra ALT_HOLD_THROTTLE_MAX - * @param sue_ALT_HOLD_PITCH_MIN Serial UDB Extra ALT_HOLD_PITCH_MIN - * @param sue_ALT_HOLD_PITCH_MAX Serial UDB Extra ALT_HOLD_PITCH_MAX - * @param sue_ALT_HOLD_PITCH_HIGH Serial UDB Extra ALT_HOLD_PITCH_HIGH - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_serial_udb_extra_f8_send(mavlink_channel_t chan, float sue_HEIGHT_TARGET_MAX, float sue_HEIGHT_TARGET_MIN, float sue_ALT_HOLD_THROTTLE_MIN, float sue_ALT_HOLD_THROTTLE_MAX, float sue_ALT_HOLD_PITCH_MIN, float sue_ALT_HOLD_PITCH_MAX, float sue_ALT_HOLD_PITCH_HIGH) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN]; - _mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX); - _mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN); - _mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN); - _mav_put_float(buf, 12, sue_ALT_HOLD_THROTTLE_MAX); - _mav_put_float(buf, 16, sue_ALT_HOLD_PITCH_MIN); - _mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX); - _mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#endif -#else - mavlink_serial_udb_extra_f8_t packet; - packet.sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX; - packet.sue_HEIGHT_TARGET_MIN = sue_HEIGHT_TARGET_MIN; - packet.sue_ALT_HOLD_THROTTLE_MIN = sue_ALT_HOLD_THROTTLE_MIN; - packet.sue_ALT_HOLD_THROTTLE_MAX = sue_ALT_HOLD_THROTTLE_MAX; - packet.sue_ALT_HOLD_PITCH_MIN = sue_ALT_HOLD_PITCH_MIN; - packet.sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX; - packet.sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)&packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_serial_udb_extra_f8_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float sue_HEIGHT_TARGET_MAX, float sue_HEIGHT_TARGET_MIN, float sue_ALT_HOLD_THROTTLE_MIN, float sue_ALT_HOLD_THROTTLE_MAX, float sue_ALT_HOLD_PITCH_MIN, float sue_ALT_HOLD_PITCH_MAX, float sue_ALT_HOLD_PITCH_HIGH) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, sue_HEIGHT_TARGET_MAX); - _mav_put_float(buf, 4, sue_HEIGHT_TARGET_MIN); - _mav_put_float(buf, 8, sue_ALT_HOLD_THROTTLE_MIN); - _mav_put_float(buf, 12, sue_ALT_HOLD_THROTTLE_MAX); - _mav_put_float(buf, 16, sue_ALT_HOLD_PITCH_MIN); - _mav_put_float(buf, 20, sue_ALT_HOLD_PITCH_MAX); - _mav_put_float(buf, 24, sue_ALT_HOLD_PITCH_HIGH); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, buf, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#endif -#else - mavlink_serial_udb_extra_f8_t *packet = (mavlink_serial_udb_extra_f8_t *)msgbuf; - packet->sue_HEIGHT_TARGET_MAX = sue_HEIGHT_TARGET_MAX; - packet->sue_HEIGHT_TARGET_MIN = sue_HEIGHT_TARGET_MIN; - packet->sue_ALT_HOLD_THROTTLE_MIN = sue_ALT_HOLD_THROTTLE_MIN; - packet->sue_ALT_HOLD_THROTTLE_MAX = sue_ALT_HOLD_THROTTLE_MAX; - packet->sue_ALT_HOLD_PITCH_MIN = sue_ALT_HOLD_PITCH_MIN; - packet->sue_ALT_HOLD_PITCH_MAX = sue_ALT_HOLD_PITCH_MAX; - packet->sue_ALT_HOLD_PITCH_HIGH = sue_ALT_HOLD_PITCH_HIGH; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8, (const char *)packet, MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SERIAL_UDB_EXTRA_F8 UNPACKING - - -/** - * @brief Get field sue_HEIGHT_TARGET_MAX from serial_udb_extra_f8 message - * - * @return Serial UDB Extra HEIGHT_TARGET_MAX - */ -static inline float mavlink_msg_serial_udb_extra_f8_get_sue_HEIGHT_TARGET_MAX(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field sue_HEIGHT_TARGET_MIN from serial_udb_extra_f8 message - * - * @return Serial UDB Extra HEIGHT_TARGET_MIN - */ -static inline float mavlink_msg_serial_udb_extra_f8_get_sue_HEIGHT_TARGET_MIN(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field sue_ALT_HOLD_THROTTLE_MIN from serial_udb_extra_f8 message - * - * @return Serial UDB Extra ALT_HOLD_THROTTLE_MIN - */ -static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_THROTTLE_MIN(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field sue_ALT_HOLD_THROTTLE_MAX from serial_udb_extra_f8 message - * - * @return Serial UDB Extra ALT_HOLD_THROTTLE_MAX - */ -static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_THROTTLE_MAX(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field sue_ALT_HOLD_PITCH_MIN from serial_udb_extra_f8 message - * - * @return Serial UDB Extra ALT_HOLD_PITCH_MIN - */ -static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_MIN(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field sue_ALT_HOLD_PITCH_MAX from serial_udb_extra_f8 message - * - * @return Serial UDB Extra ALT_HOLD_PITCH_MAX - */ -static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_MAX(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field sue_ALT_HOLD_PITCH_HIGH from serial_udb_extra_f8 message - * - * @return Serial UDB Extra ALT_HOLD_PITCH_HIGH - */ -static inline float mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_HIGH(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Decode a serial_udb_extra_f8 message into a struct - * - * @param msg The message to decode - * @param serial_udb_extra_f8 C-struct to decode the message contents into - */ -static inline void mavlink_msg_serial_udb_extra_f8_decode(const mavlink_message_t* msg, mavlink_serial_udb_extra_f8_t* serial_udb_extra_f8) -{ -#if MAVLINK_NEED_BYTE_SWAP - serial_udb_extra_f8->sue_HEIGHT_TARGET_MAX = mavlink_msg_serial_udb_extra_f8_get_sue_HEIGHT_TARGET_MAX(msg); - serial_udb_extra_f8->sue_HEIGHT_TARGET_MIN = mavlink_msg_serial_udb_extra_f8_get_sue_HEIGHT_TARGET_MIN(msg); - serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MIN = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_THROTTLE_MIN(msg); - serial_udb_extra_f8->sue_ALT_HOLD_THROTTLE_MAX = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_THROTTLE_MAX(msg); - serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MIN = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_MIN(msg); - serial_udb_extra_f8->sue_ALT_HOLD_PITCH_MAX = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_MAX(msg); - serial_udb_extra_f8->sue_ALT_HOLD_PITCH_HIGH = mavlink_msg_serial_udb_extra_f8_get_sue_ALT_HOLD_PITCH_HIGH(msg); -#else - memcpy(serial_udb_extra_f8, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SERIAL_UDB_EXTRA_F8_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/matrixpilot/testsuite.h b/mavlink/include/mavlink/v1.0/matrixpilot/testsuite.h deleted file mode 100644 index 6856839e9..000000000 --- a/mavlink/include/mavlink/v1.0/matrixpilot/testsuite.h +++ /dev/null @@ -1,1240 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from matrixpilot.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef MATRIXPILOT_TESTSUITE_H -#define MATRIXPILOT_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); -static void mavlink_test_matrixpilot(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_test_common(system_id, component_id, last_msg); - mavlink_test_matrixpilot(system_id, component_id, last_msg); -} -#endif - -#include "../common/testsuite.h" - - -static void mavlink_test_flexifunction_set(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_flexifunction_set_t packet_in = { - 5, - }72, - }; - mavlink_flexifunction_set_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.target_system = packet_in.target_system; - packet1.target_component = packet_in.target_component; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_flexifunction_set_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_flexifunction_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_flexifunction_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_flexifunction_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_flexifunction_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component ); - mavlink_msg_flexifunction_set_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; i - -#ifndef M_PI_2 - #define M_PI_2 ((float)asin(1)) -#endif - -/** - * @file mavlink_conversions.h - * - * These conversion functions follow the NASA rotation standards definition file - * available online. - * - * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free - * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free) - * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the - * protocol as widely as possible. - * - * @author James Goppert - */ - -MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3]) -{ - double a = quaternion[0]; - double b = quaternion[1]; - double c = quaternion[2]; - double d = quaternion[3]; - double aSq = a * a; - double bSq = b * b; - double cSq = c * c; - double dSq = d * d; - dcm[0][0] = aSq + bSq - cSq - dSq; - dcm[0][1] = 2.0 * (b * c - a * d); - dcm[0][2] = 2.0 * (a * c + b * d); - dcm[1][0] = 2.0 * (b * c + a * d); - dcm[1][1] = aSq - bSq + cSq - dSq; - dcm[1][2] = 2.0 * (c * d - a * b); - dcm[2][0] = 2.0 * (b * d - a * c); - dcm[2][1] = 2.0 * (a * b + c * d); - dcm[2][2] = aSq - bSq - cSq + dSq; -} - -MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw) -{ - float phi, theta, psi; - theta = asin(-dcm[2][0]); - - if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) { - phi = 0.0f; - psi = (atan2f(dcm[1][2] - dcm[0][1], - dcm[0][2] + dcm[1][1]) + phi); - - } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) { - phi = 0.0f; - psi = atan2f(dcm[1][2] - dcm[0][1], - dcm[0][2] + dcm[1][1] - phi); - - } else { - phi = atan2f(dcm[2][1], dcm[2][2]); - psi = atan2f(dcm[1][0], dcm[0][0]); - } - - *roll = phi; - *pitch = theta; - *yaw = psi; -} - -MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw) -{ - float dcm[3][3]; - mavlink_quaternion_to_dcm(quaternion, dcm); - mavlink_dcm_to_euler(dcm, roll, pitch, yaw); -} - -MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4]) -{ - double cosPhi_2 = cos((double)roll / 2.0); - double sinPhi_2 = sin((double)roll / 2.0); - double cosTheta_2 = cos((double)pitch / 2.0); - double sinTheta_2 = sin((double)pitch / 2.0); - double cosPsi_2 = cos((double)yaw / 2.0); - double sinPsi_2 = sin((double)yaw / 2.0); - quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 + - sinPhi_2 * sinTheta_2 * sinPsi_2); - quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 - - cosPhi_2 * sinTheta_2 * sinPsi_2); - quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 + - sinPhi_2 * cosTheta_2 * sinPsi_2); - quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 - - sinPhi_2 * sinTheta_2 * cosPsi_2); -} - -MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4]) -{ - quaternion[0] = (0.5 * sqrt(1.0 + - (double)(dcm[0][0] + dcm[1][1] + dcm[2][2]))); - quaternion[1] = (0.5 * sqrt(1.0 + - (double)(dcm[0][0] - dcm[1][1] - dcm[2][2]))); - quaternion[2] = (0.5 * sqrt(1.0 + - (double)(-dcm[0][0] + dcm[1][1] - dcm[2][2]))); - quaternion[3] = (0.5 * sqrt(1.0 + - (double)(-dcm[0][0] - dcm[1][1] + dcm[2][2]))); -} - -MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3]) -{ - double cosPhi = cos(roll); - double sinPhi = sin(roll); - double cosThe = cos(pitch); - double sinThe = sin(pitch); - double cosPsi = cos(yaw); - double sinPsi = sin(yaw); - - dcm[0][0] = cosThe * cosPsi; - dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi; - dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi; - - dcm[1][0] = cosThe * sinPsi; - dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi; - dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi; - - dcm[2][0] = -sinThe; - dcm[2][1] = sinPhi * cosThe; - dcm[2][2] = cosPhi * cosThe; -} - -#endif diff --git a/mavlink/include/mavlink/v1.0/mavlink_helpers.h b/mavlink/include/mavlink/v1.0/mavlink_helpers.h deleted file mode 100644 index 1639a830b..000000000 --- a/mavlink/include/mavlink/v1.0/mavlink_helpers.h +++ /dev/null @@ -1,574 +0,0 @@ -#ifndef _MAVLINK_HELPERS_H_ -#define _MAVLINK_HELPERS_H_ - -#include "string.h" -#include "checksum.h" -#include "mavlink_types.h" -#include "mavlink_conversions.h" - -#ifndef MAVLINK_HELPER -#define MAVLINK_HELPER -#endif - -/* - * Internal function to give access to the channel status for each channel - */ -#ifndef MAVLINK_GET_CHANNEL_STATUS -MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) -{ -#if MAVLINK_EXTERNAL_RX_STATUS - // No m_mavlink_status array defined in function, - // has to be defined externally -#else - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; -#endif - return &m_mavlink_status[chan]; -} -#endif - -/* - * Internal function to give access to the channel buffer for each channel - */ -#ifndef MAVLINK_GET_CHANNEL_BUFFER -MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) -{ - -#if MAVLINK_EXTERNAL_RX_BUFFER - // No m_mavlink_buffer array defined in function, - // has to be defined externally -#else - static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; -#endif - return &m_mavlink_buffer[chan]; -} -#endif - -/** - * @brief Reset the status of a channel. - */ -MAVLINK_HELPER void mavlink_reset_channel_status(uint8_t chan) -{ - mavlink_status_t *status = mavlink_get_channel_status(chan); - status->parse_state = MAVLINK_PARSE_STATE_IDLE; -} - -/** - * @brief Finalize a MAVLink message with channel assignment - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. This function - * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack - * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. - * - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length) -#endif -{ - // This code part is the same for all messages; - msg->magic = MAVLINK_STX; - msg->len = length; - msg->sysid = system_id; - msg->compid = component_id; - // One sequence number per component - msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; - mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; - msg->checksum = crc_calculate(((const uint8_t*)(msg)) + 3, MAVLINK_CORE_HEADER_LEN); - crc_accumulate_buffer(&msg->checksum, _MAV_PAYLOAD(msg), msg->len); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &msg->checksum); -#endif - mavlink_ck_a(msg) = (uint8_t)(msg->checksum & 0xFF); - mavlink_ck_b(msg) = (uint8_t)(msg->checksum >> 8); - - return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - - -/** - * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length, uint8_t crc_extra) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); -} -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); -} -#endif - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); - -/** - * @brief Finalize a MAVLink message with channel assignment and send - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, - uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) -#endif -{ - uint16_t checksum; - uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; - uint8_t ck[2]; - mavlink_status_t *status = mavlink_get_channel_status(chan); - buf[0] = MAVLINK_STX; - buf[1] = length; - buf[2] = status->current_tx_seq; - buf[3] = mavlink_system.sysid; - buf[4] = mavlink_system.compid; - buf[5] = msgid; - status->current_tx_seq++; - checksum = crc_calculate((const uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); - crc_accumulate_buffer(&checksum, packet, length); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); -#endif - ck[0] = (uint8_t)(checksum & 0xFF); - ck[1] = (uint8_t)(checksum >> 8); - - MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); - _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); - _mavlink_send_uart(chan, packet, length); - _mavlink_send_uart(chan, (const char *)ck, 2); - MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); -} - -/** - * @brief re-send a message over a uart channel - * this is more stack efficient than re-marshalling the message - */ -MAVLINK_HELPER void _mavlink_resend_uart(mavlink_channel_t chan, const mavlink_message_t *msg) -{ - uint8_t ck[2]; - - ck[0] = (uint8_t)(msg->checksum & 0xFF); - ck[1] = (uint8_t)(msg->checksum >> 8); - // XXX use the right sequence here - - MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); - _mavlink_send_uart(chan, (const char *)&msg->magic, MAVLINK_NUM_HEADER_BYTES); - _mavlink_send_uart(chan, _MAV_PAYLOAD(msg), msg->len); - _mavlink_send_uart(chan, (const char *)ck, 2); - MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + msg->len); -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -/** - * @brief Pack a message to send it over a serial byte stream - */ -MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) -{ - memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); - - uint8_t *ck = buffer + (MAVLINK_NUM_HEADER_BYTES + (uint16_t)msg->len); - - ck[0] = (uint8_t)(msg->checksum & 0xFF); - ck[1] = (uint8_t)(msg->checksum >> 8); - - return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; -} - -union __mavlink_bitfield { - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; -}; - - -MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) -{ - crc_init(&msg->checksum); -} - -MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) -{ - crc_accumulate(c, &msg->checksum); -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. Checksum and other failures will be silently - * ignored. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to barse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @return 0 if no message could be decoded, 1 else - * - * A typical use scenario of this function call is: - * - * @code - * #include // For fixed-width uint8_t type - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg)) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - /* - default message crc function. You can override this per-system to - put this data in a different memory segment - */ -#if MAVLINK_CRC_EXTRA -#ifndef MAVLINK_MESSAGE_CRC - static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; -#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] -#endif -#endif - -/* Enable this option to check the length of each message. - This allows invalid messages to be caught much sooner. Use if the transmission - medium is prone to missing (or extra) characters (e.g. a radio that fades in - and out). Only use if the channel will only contain messages types listed in - the headers. -*/ -#if MAVLINK_CHECK_MESSAGE_LENGTH -#ifndef MAVLINK_MESSAGE_LENGTH - static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; -#define MAVLINK_MESSAGE_LENGTH(msgid) mavlink_message_lengths[msgid] -#endif -#endif - - mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message - mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status - int bufferIndex = 0; - - status->msg_received = 0; - - switch (status->parse_state) - { - case MAVLINK_PARSE_STATE_UNINIT: - case MAVLINK_PARSE_STATE_IDLE: - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - rxmsg->magic = c; - mavlink_start_checksum(rxmsg); - } - break; - - case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received -/* Support shorter buffers than the - default maximum packet size */ -#if (MAVLINK_MAX_PAYLOAD_LEN < 255) - || c > MAVLINK_MAX_PAYLOAD_LEN -#endif - ) - { - status->buffer_overrun++; - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - } - else - { - // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 - rxmsg->len = c; - status->packet_idx = 0; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; - } - break; - - case MAVLINK_PARSE_STATE_GOT_LENGTH: - rxmsg->seq = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; - break; - - case MAVLINK_PARSE_STATE_GOT_SEQ: - rxmsg->sysid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; - break; - - case MAVLINK_PARSE_STATE_GOT_SYSID: - rxmsg->compid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPID: -#if MAVLINK_CHECK_MESSAGE_LENGTH - if (rxmsg->len != MAVLINK_MESSAGE_LENGTH(c)) - { - status->parse_error++; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - break; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - mavlink_start_checksum(rxmsg); - } - } -#endif - rxmsg->msgid = c; - mavlink_update_checksum(rxmsg, c); - if (rxmsg->len == 0) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; - } - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID: - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; - mavlink_update_checksum(rxmsg, c); - if (status->packet_idx == rxmsg->len) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - break; - - case MAVLINK_PARSE_STATE_GOT_PAYLOAD: -#if MAVLINK_CRC_EXTRA - mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); -#endif - if (c != (rxmsg->checksum & 0xFF)) { - // Check first checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; - } - break; - - case MAVLINK_PARSE_STATE_GOT_CRC1: - if (c != (rxmsg->checksum >> 8)) { - // Check second checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - } - else - { - // Successfully got message - status->msg_received = 1; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - } - break; - } - - bufferIndex++; - // If a message has been sucessfully decoded, check index - if (status->msg_received == 1) - { - //while(status->current_seq != rxmsg->seq) - //{ - // status->packet_rx_drop_count++; - // status->current_seq++; - //} - status->current_rx_seq = rxmsg->seq; - // Initial condition: If no packet has been received so far, drop count is undefined - if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; - // Count this packet as received - status->packet_rx_success_count++; - } - - r_mavlink_status->current_rx_seq = status->current_rx_seq+1; - r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; - r_mavlink_status->packet_rx_drop_count = status->parse_error; - status->parse_error = 0; - return status->msg_received; -} - -/** - * @brief Put a bitfield of length 1-32 bit into the buffer - * - * @param b the value to add, will be encoded in the bitfield - * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. - * @param packet_index the position in the packet (the index of the first byte to use) - * @param bit_index the position in the byte (the index of the first bit to use) - * @param buffer packet buffer to write into - * @return new position of the last used byte in the buffer - */ -MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) -{ - uint16_t bits_remain = bits; - // Transform number into network order - int32_t v; - uint8_t i_bit_index, i_byte_index, curr_bits_n; -#if MAVLINK_NEED_BYTE_SWAP - union { - int32_t i; - uint8_t b[4]; - } bin, bout; - bin.i = b; - bout.b[0] = bin.b[3]; - bout.b[1] = bin.b[2]; - bout.b[2] = bin.b[1]; - bout.b[3] = bin.b[0]; - v = bout.i; -#else - v = b; -#endif - - // buffer in - // 01100000 01000000 00000000 11110001 - // buffer out - // 11110001 00000000 01000000 01100000 - - // Existing partly filled byte (four free slots) - // 0111xxxx - - // Mask n free bits - // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 - // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 - - // Shift n bits into the right position - // out = in >> n; - - // Mask and shift bytes - i_bit_index = bit_index; - i_byte_index = packet_index; - if (bit_index > 0) - { - // If bits were available at start, they were available - // in the byte before the current index - i_byte_index--; - } - - // While bits have not been packed yet - while (bits_remain > 0) - { - // Bits still have to be packed - // there can be more than 8 bits, so - // we might have to pack them into more than one byte - - // First pack everything we can into the current 'open' byte - //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 - //FIXME - if (bits_remain <= (uint8_t)(8 - i_bit_index)) - { - // Enough space - curr_bits_n = (uint8_t)bits_remain; - } - else - { - curr_bits_n = (8 - i_bit_index); - } - - // Pack these n bits into the current byte - // Mask out whatever was at that position with ones (xxx11111) - buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); - // Put content to this position, by masking out the non-used part - buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); - - // Increment the bit index - i_bit_index += curr_bits_n; - - // Now proceed to the next byte, if necessary - bits_remain -= curr_bits_n; - if (bits_remain > 0) - { - // Offer another 8 bits / one byte - i_byte_index++; - i_bit_index = 0; - } - } - - *r_bit_index = i_bit_index; - // If a partly filled byte is present, mark this as consumed - if (i_bit_index != 7) i_byte_index++; - return i_byte_index - packet_index; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -// To make MAVLink work on your MCU, define comm_send_ch() if you wish -// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a -// whole packet at a time - -/* - -#include "mavlink_types.h" - -void comm_send_ch(mavlink_channel_t chan, uint8_t ch) -{ - if (chan == MAVLINK_COMM_0) - { - uart0_transmit(ch); - } - if (chan == MAVLINK_COMM_1) - { - uart1_transmit(ch); - } -} - */ - -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) -{ -#ifdef MAVLINK_SEND_UART_BYTES - /* this is the more efficient approach, if the platform - defines it */ - MAVLINK_SEND_UART_BYTES(chan, (const uint8_t *)buf, len); -#else - /* fallback to one byte at a time */ - uint16_t i; - for (i = 0; i < len; i++) { - comm_send_ch(chan, (uint8_t)buf[i]); - } -#endif -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/mavlink/include/mavlink/v1.0/mavlink_protobuf_manager.hpp b/mavlink/include/mavlink/v1.0/mavlink_protobuf_manager.hpp deleted file mode 100644 index fd3ddd026..000000000 --- a/mavlink/include/mavlink/v1.0/mavlink_protobuf_manager.hpp +++ /dev/null @@ -1,377 +0,0 @@ -#ifndef MAVLINKPROTOBUFMANAGER_HPP -#define MAVLINKPROTOBUFMANAGER_HPP - -#include -#include -#include -#include - -#include -#include -#include -#include - -namespace mavlink -{ - -class ProtobufManager -{ -public: - ProtobufManager() - : mRegisteredTypeCount(0) - , mStreamID(0) - , mVerbose(false) - , kExtendedHeaderSize(MAVLINK_EXTENDED_HEADER_LEN) - , kExtendedPayloadMaxSize(MAVLINK_MAX_EXTENDED_PAYLOAD_LEN) - { - // register GLOverlay - { - std::tr1::shared_ptr msg(new px::GLOverlay); - registerType(msg); - } - - // register ObstacleList - { - std::tr1::shared_ptr msg(new px::ObstacleList); - registerType(msg); - } - - // register ObstacleMap - { - std::tr1::shared_ptr msg(new px::ObstacleMap); - registerType(msg); - } - - // register Path - { - std::tr1::shared_ptr msg(new px::Path); - registerType(msg); - } - - // register PointCloudXYZI - { - std::tr1::shared_ptr msg(new px::PointCloudXYZI); - registerType(msg); - } - - // register PointCloudXYZRGB - { - std::tr1::shared_ptr msg(new px::PointCloudXYZRGB); - registerType(msg); - } - - // register RGBDImage - { - std::tr1::shared_ptr msg(new px::RGBDImage); - registerType(msg); - } - - srand(time(NULL)); - mStreamID = rand() + 1; - } - - bool fragmentMessage(uint8_t system_id, uint8_t component_id, - uint8_t target_system, uint8_t target_component, - const google::protobuf::Message& protobuf_msg, - std::vector& fragments) const - { - TypeMap::const_iterator it = mTypeMap.find(protobuf_msg.GetTypeName()); - if (it == mTypeMap.end()) - { - std::cout << "# WARNING: Protobuf message with type " - << protobuf_msg.GetTypeName() << " is not registered." - << std::endl; - return false; - } - - uint8_t typecode = it->second; - - std::string data = protobuf_msg.SerializeAsString(); - - int fragmentCount = (protobuf_msg.ByteSize() + kExtendedPayloadMaxSize - 1) / kExtendedPayloadMaxSize; - unsigned int offset = 0; - - for (int i = 0; i < fragmentCount; ++i) - { - mavlink_extended_message_t fragment; - - // write extended header data - uint8_t* payload = reinterpret_cast(fragment.base_msg.payload64); - unsigned int length = 0; - uint8_t flags = 0; - - if (i < fragmentCount - 1) - { - length = kExtendedPayloadMaxSize; - flags |= 0x1; - } - else - { - length = protobuf_msg.ByteSize() - kExtendedPayloadMaxSize * (fragmentCount - 1); - } - - memcpy(payload, &target_system, 1); - memcpy(payload + 1, &target_component, 1); - memcpy(payload + 2, &typecode, 1); - memcpy(payload + 3, &length, 4); - memcpy(payload + 7, &mStreamID, 2); - memcpy(payload + 9, &offset, 4); - memcpy(payload + 13, &flags, 1); - - fragment.base_msg.msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE; - mavlink_finalize_message(&fragment.base_msg, system_id, component_id, kExtendedHeaderSize, 0); - - // write extended payload data - fragment.extended_payload_len = length; - memcpy(fragment.extended_payload, &data[offset], length); - - fragments.push_back(fragment); - offset += length; - } - - if (mVerbose) - { - std::cerr << "# INFO: Split extended message with size " - << protobuf_msg.ByteSize() << " into " - << fragmentCount << " fragments." << std::endl; - } - - return true; - } - - bool cacheFragment(mavlink_extended_message_t& msg) - { - if (!validFragment(msg)) - { - if (mVerbose) - { - std::cerr << "# WARNING: Message is not a valid fragment. " - << "Dropping message..." << std::endl; - } - return false; - } - - // read extended header - uint8_t* payload = reinterpret_cast(msg.base_msg.payload64); - uint8_t typecode = 0; - unsigned int length = 0; - unsigned short streamID = 0; - unsigned int offset = 0; - uint8_t flags = 0; - - memcpy(&typecode, payload + 2, 1); - memcpy(&length, payload + 3, 4); - memcpy(&streamID, payload + 7, 2); - memcpy(&offset, payload + 9, 4); - memcpy(&flags, payload + 13, 1); - - if (typecode >= mTypeMap.size()) - { - std::cout << "# WARNING: Protobuf message with type code " - << static_cast(typecode) << " is not registered." << std::endl; - return false; - } - - bool reassemble = false; - - FragmentQueue::iterator it = mFragmentQueue.find(streamID); - if (it == mFragmentQueue.end()) - { - if (offset == 0) - { - mFragmentQueue[streamID].push_back(msg); - - if ((flags & 0x1) != 0x1) - { - reassemble = true; - } - - if (mVerbose) - { - std::cerr << "# INFO: Added fragment to new queue." - << std::endl; - } - } - else - { - if (mVerbose) - { - std::cerr << "# WARNING: Message is not a valid fragment. " - << "Dropping message..." << std::endl; - } - } - } - else - { - std::deque& queue = it->second; - - if (queue.empty()) - { - if (offset == 0) - { - queue.push_back(msg); - - if ((flags & 0x1) != 0x1) - { - reassemble = true; - } - } - else - { - if (mVerbose) - { - std::cerr << "# WARNING: Message is not a valid fragment. " - << "Dropping message..." << std::endl; - } - } - } - else - { - if (fragmentDataSize(queue.back()) + fragmentOffset(queue.back()) != offset) - { - if (mVerbose) - { - std::cerr << "# WARNING: Previous fragment(s) have been lost. " - << "Dropping message and clearing queue..." << std::endl; - } - queue.clear(); - } - else - { - queue.push_back(msg); - - if ((flags & 0x1) != 0x1) - { - reassemble = true; - } - } - } - } - - if (reassemble) - { - std::deque& queue = mFragmentQueue[streamID]; - - std::string data; - for (size_t i = 0; i < queue.size(); ++i) - { - mavlink_extended_message_t& mavlink_msg = queue.at(i); - - data.append(reinterpret_cast(&mavlink_msg.extended_payload[0]), - static_cast(mavlink_msg.extended_payload_len)); - } - - mMessages.at(typecode)->ParseFromString(data); - - mMessageAvailable.at(typecode) = true; - - queue.clear(); - - if (mVerbose) - { - std::cerr << "# INFO: Reassembled fragments for message with typename " - << mMessages.at(typecode)->GetTypeName() << " and size " - << mMessages.at(typecode)->ByteSize() - << "." << std::endl; - } - } - - return true; - } - - bool getMessage(std::tr1::shared_ptr& msg) - { - for (size_t i = 0; i < mMessageAvailable.size(); ++i) - { - if (mMessageAvailable.at(i)) - { - msg = mMessages.at(i); - mMessageAvailable.at(i) = false; - - return true; - } - } - - return false; - } - -private: - void registerType(const std::tr1::shared_ptr& msg) - { - mTypeMap[msg->GetTypeName()] = mRegisteredTypeCount; - ++mRegisteredTypeCount; - mMessages.push_back(msg); - mMessageAvailable.push_back(false); - } - - bool validFragment(const mavlink_extended_message_t& msg) const - { - if (msg.base_msg.magic != MAVLINK_STX || - msg.base_msg.len != kExtendedHeaderSize || - msg.base_msg.msgid != MAVLINK_MSG_ID_EXTENDED_MESSAGE) - { - return false; - } - - uint16_t checksum; - checksum = crc_calculate(reinterpret_cast(&msg.base_msg.len), MAVLINK_CORE_HEADER_LEN); - crc_accumulate_buffer(&checksum, reinterpret_cast(&msg.base_msg.payload64), kExtendedHeaderSize); -#if MAVLINK_CRC_EXTRA - static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; - crc_accumulate(mavlink_message_crcs[msg.base_msg.msgid], &checksum); -#endif - - if (mavlink_ck_a(&(msg.base_msg)) != (uint8_t)(checksum & 0xFF) && - mavlink_ck_b(&(msg.base_msg)) != (uint8_t)(checksum >> 8)) - { - return false; - } - - return true; - } - - unsigned int fragmentDataSize(const mavlink_extended_message_t& msg) const - { - const uint8_t* payload = reinterpret_cast(msg.base_msg.payload64); - - return *(reinterpret_cast(payload + 3)); - } - - unsigned int fragmentOffset(const mavlink_extended_message_t& msg) const - { - const uint8_t* payload = reinterpret_cast(msg.base_msg.payload64); - - return *(reinterpret_cast(payload + 9)); - } - - int mRegisteredTypeCount; - unsigned short mStreamID; - bool mVerbose; - - typedef std::map TypeMap; - TypeMap mTypeMap; - std::vector< std::tr1::shared_ptr > mMessages; - std::vector mMessageAvailable; - - typedef std::map > FragmentQueue; - FragmentQueue mFragmentQueue; - - const int kExtendedHeaderSize; - /** - * Extended header structure - * ========================= - * byte 0 - target_system - * byte 1 - target_component - * byte 2 - extended message id (type code) - * bytes 3-6 - extended payload size in bytes - * byte 7-8 - stream ID - * byte 9-12 - fragment offset - * byte 13 - fragment flags (bit 0 - 1=more fragments, 0=last fragment) - */ - - const int kExtendedPayloadMaxSize; -}; - -} - -#endif diff --git a/mavlink/include/mavlink/v1.0/mavlink_types.h b/mavlink/include/mavlink/v1.0/mavlink_types.h deleted file mode 100644 index 43658e629..000000000 --- a/mavlink/include/mavlink/v1.0/mavlink_types.h +++ /dev/null @@ -1,161 +0,0 @@ -#ifndef MAVLINK_TYPES_H_ -#define MAVLINK_TYPES_H_ - -#include - -#ifndef MAVLINK_MAX_PAYLOAD_LEN -// it is possible to override this, but be careful! -#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length -#endif - -#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) -#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum -#define MAVLINK_NUM_CHECKSUM_BYTES 2 -#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) - -#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length - -#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 -#define MAVLINK_EXTENDED_HEADER_LEN 14 - -#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__) - /* full fledged 32bit++ OS */ - #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 -#else - /* small microcontrollers */ - #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 -#endif - -#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) - -#pragma pack(push, 1) -typedef struct param_union { - union { - float param_float; - int32_t param_int32; - uint32_t param_uint32; - int16_t param_int16; - uint16_t param_uint16; - int8_t param_int8; - uint8_t param_uint8; - uint8_t bytes[4]; - }; - uint8_t type; -} mavlink_param_union_t; - -typedef struct __mavlink_system { - uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t type; ///< Unused, can be used by user to store the system's type - uint8_t state; ///< Unused, can be used by user to store the system's state - uint8_t mode; ///< Unused, can be used by user to store the system's mode - uint32_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode -} mavlink_system_t; - -typedef struct __mavlink_message { - uint16_t checksum; /// sent at end of packet - uint8_t magic; ///< protocol magic marker - uint8_t len; ///< Length of payload - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint8_t msgid; ///< ID of message in payload - uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; -} mavlink_message_t; - -typedef struct __mavlink_extended_message { - mavlink_message_t base_msg; - int32_t extended_payload_len; ///< Length of extended payload if any - uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; -} mavlink_extended_message_t; -#pragma pack(pop) - -typedef enum { - MAVLINK_TYPE_CHAR = 0, - MAVLINK_TYPE_UINT8_T = 1, - MAVLINK_TYPE_INT8_T = 2, - MAVLINK_TYPE_UINT16_T = 3, - MAVLINK_TYPE_INT16_T = 4, - MAVLINK_TYPE_UINT32_T = 5, - MAVLINK_TYPE_INT32_T = 6, - MAVLINK_TYPE_UINT64_T = 7, - MAVLINK_TYPE_INT64_T = 8, - MAVLINK_TYPE_FLOAT = 9, - MAVLINK_TYPE_DOUBLE = 10 -} mavlink_message_type_t; - -#define MAVLINK_MAX_FIELDS 64 - -typedef struct __mavlink_field_info { - const char *name; // name of this field - const char *print_format; // printing format hint, or NULL - mavlink_message_type_t type; // type of this field - unsigned int array_length; // if non-zero, field is an array - unsigned int wire_offset; // offset of each field in the payload - unsigned int structure_offset; // offset in a C structure -} mavlink_field_info_t; - -// note that in this structure the order of fields is the order -// in the XML file, not necessary the wire order -typedef struct __mavlink_message_info { - const char *name; // name of the message - unsigned num_fields; // how many fields in this message - mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information -} mavlink_message_info_t; - -#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) -#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) - -// checksum is immediately after the payload bytes -#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) -#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) - -typedef enum { - MAVLINK_COMM_0, - MAVLINK_COMM_1, - MAVLINK_COMM_2, - MAVLINK_COMM_3 -} mavlink_channel_t; - -/* - * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number - * of buffers they will use. If more are used, then the result will be - * a stack overrun - */ -#ifndef MAVLINK_COMM_NUM_BUFFERS -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) -# define MAVLINK_COMM_NUM_BUFFERS 16 -#else -# define MAVLINK_COMM_NUM_BUFFERS 4 -#endif -#endif - -typedef enum { - MAVLINK_PARSE_STATE_UNINIT=0, - MAVLINK_PARSE_STATE_IDLE, - MAVLINK_PARSE_STATE_GOT_STX, - MAVLINK_PARSE_STATE_GOT_SEQ, - MAVLINK_PARSE_STATE_GOT_LENGTH, - MAVLINK_PARSE_STATE_GOT_SYSID, - MAVLINK_PARSE_STATE_GOT_COMPID, - MAVLINK_PARSE_STATE_GOT_MSGID, - MAVLINK_PARSE_STATE_GOT_PAYLOAD, - MAVLINK_PARSE_STATE_GOT_CRC1 -} mavlink_parse_state_t; ///< The state machine for the comm parser - -typedef struct __mavlink_status { - uint8_t msg_received; ///< Number of received messages - uint8_t buffer_overrun; ///< Number of buffer overruns - uint8_t parse_error; ///< Number of parse errors - mavlink_parse_state_t parse_state; ///< Parsing state machine - uint8_t packet_idx; ///< Index in current packet - uint8_t current_rx_seq; ///< Sequence number of last packet received - uint8_t current_tx_seq; ///< Sequence number of last packet sent - uint16_t packet_rx_success_count; ///< Received packets - uint16_t packet_rx_drop_count; ///< Number of packet drops -} mavlink_status_t; - -#define MAVLINK_BIG_ENDIAN 0 -#define MAVLINK_LITTLE_ENDIAN 1 - -#endif /* MAVLINK_TYPES_H_ */ diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink.h deleted file mode 100644 index f06223370..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink.h +++ /dev/null @@ -1,27 +0,0 @@ -/** @file - * @brief MAVLink comm protocol built from pixhawk.xml - * @see http://pixhawk.ethz.ch/software/mavlink - */ -#ifndef MAVLINK_H -#define MAVLINK_H - -#ifndef MAVLINK_STX -#define MAVLINK_STX 254 -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS 1 -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA 1 -#endif - -#include "version.h" -#include "pixhawk.h" - -#endif // MAVLINK_H diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h deleted file mode 100644 index f1cac9f2c..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_attitude_control.h +++ /dev/null @@ -1,401 +0,0 @@ -// MESSAGE ATTITUDE_CONTROL PACKING - -#define MAVLINK_MSG_ID_ATTITUDE_CONTROL 200 - -typedef struct __mavlink_attitude_control_t -{ - float roll; ///< roll - float pitch; ///< pitch - float yaw; ///< yaw - float thrust; ///< thrust - uint8_t target; ///< The system to be controlled - uint8_t roll_manual; ///< roll control enabled auto:0, manual:1 - uint8_t pitch_manual; ///< pitch auto:0, manual:1 - uint8_t yaw_manual; ///< yaw auto:0, manual:1 - uint8_t thrust_manual; ///< thrust auto:0, manual:1 -} mavlink_attitude_control_t; - -#define MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN 21 -#define MAVLINK_MSG_ID_200_LEN 21 - -#define MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC 254 -#define MAVLINK_MSG_ID_200_CRC 254 - - - -#define MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL { \ - "ATTITUDE_CONTROL", \ - 9, \ - { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_attitude_control_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_control_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_control_t, yaw) }, \ - { "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_control_t, thrust) }, \ - { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_attitude_control_t, target) }, \ - { "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_attitude_control_t, roll_manual) }, \ - { "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_attitude_control_t, pitch_manual) }, \ - { "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_attitude_control_t, yaw_manual) }, \ - { "thrust_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_attitude_control_t, thrust_manual) }, \ - } \ -} - - -/** - * @brief Pack a attitude_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target The system to be controlled - * @param roll roll - * @param pitch pitch - * @param yaw yaw - * @param thrust thrust - * @param roll_manual roll control enabled auto:0, manual:1 - * @param pitch_manual pitch auto:0, manual:1 - * @param yaw_manual yaw auto:0, manual:1 - * @param thrust_manual thrust auto:0, manual:1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target); - _mav_put_uint8_t(buf, 17, roll_manual); - _mav_put_uint8_t(buf, 18, pitch_manual); - _mav_put_uint8_t(buf, 19, yaw_manual); - _mav_put_uint8_t(buf, 20, thrust_manual); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#else - mavlink_attitude_control_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.target = target; - packet.roll_manual = roll_manual; - packet.pitch_manual = pitch_manual; - packet.yaw_manual = yaw_manual; - packet.thrust_manual = thrust_manual; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#endif -} - -/** - * @brief Pack a attitude_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target The system to be controlled - * @param roll roll - * @param pitch pitch - * @param yaw yaw - * @param thrust thrust - * @param roll_manual roll control enabled auto:0, manual:1 - * @param pitch_manual pitch auto:0, manual:1 - * @param yaw_manual yaw auto:0, manual:1 - * @param thrust_manual thrust auto:0, manual:1 - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_attitude_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target,float roll,float pitch,float yaw,float thrust,uint8_t roll_manual,uint8_t pitch_manual,uint8_t yaw_manual,uint8_t thrust_manual) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target); - _mav_put_uint8_t(buf, 17, roll_manual); - _mav_put_uint8_t(buf, 18, pitch_manual); - _mav_put_uint8_t(buf, 19, yaw_manual); - _mav_put_uint8_t(buf, 20, thrust_manual); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#else - mavlink_attitude_control_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.target = target; - packet.roll_manual = roll_manual; - packet.pitch_manual = pitch_manual; - packet.yaw_manual = yaw_manual; - packet.thrust_manual = thrust_manual; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_ATTITUDE_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#endif -} - -/** - * @brief Encode a attitude_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param attitude_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control) -{ - return mavlink_msg_attitude_control_pack(system_id, component_id, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual); -} - -/** - * @brief Encode a attitude_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param attitude_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_attitude_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_control_t* attitude_control) -{ - return mavlink_msg_attitude_control_pack_chan(system_id, component_id, chan, msg, attitude_control->target, attitude_control->roll, attitude_control->pitch, attitude_control->yaw, attitude_control->thrust, attitude_control->roll_manual, attitude_control->pitch_manual, attitude_control->yaw_manual, attitude_control->thrust_manual); -} - -/** - * @brief Send a attitude_control message - * @param chan MAVLink channel to send the message - * - * @param target The system to be controlled - * @param roll roll - * @param pitch pitch - * @param yaw yaw - * @param thrust thrust - * @param roll_manual roll control enabled auto:0, manual:1 - * @param pitch_manual pitch auto:0, manual:1 - * @param yaw_manual yaw auto:0, manual:1 - * @param thrust_manual thrust auto:0, manual:1 - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_attitude_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN]; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target); - _mav_put_uint8_t(buf, 17, roll_manual); - _mav_put_uint8_t(buf, 18, pitch_manual); - _mav_put_uint8_t(buf, 19, yaw_manual); - _mav_put_uint8_t(buf, 20, thrust_manual); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#endif -#else - mavlink_attitude_control_t packet; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.thrust = thrust; - packet.target = target; - packet.roll_manual = roll_manual; - packet.pitch_manual = pitch_manual; - packet.yaw_manual = yaw_manual; - packet.thrust_manual = thrust_manual; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_attitude_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, roll); - _mav_put_float(buf, 4, pitch); - _mav_put_float(buf, 8, yaw); - _mav_put_float(buf, 12, thrust); - _mav_put_uint8_t(buf, 16, target); - _mav_put_uint8_t(buf, 17, roll_manual); - _mav_put_uint8_t(buf, 18, pitch_manual); - _mav_put_uint8_t(buf, 19, yaw_manual); - _mav_put_uint8_t(buf, 20, thrust_manual); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, buf, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#endif -#else - mavlink_attitude_control_t *packet = (mavlink_attitude_control_t *)msgbuf; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->thrust = thrust; - packet->target = target; - packet->roll_manual = roll_manual; - packet->pitch_manual = pitch_manual; - packet->yaw_manual = yaw_manual; - packet->thrust_manual = thrust_manual; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN, MAVLINK_MSG_ID_ATTITUDE_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_CONTROL, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE ATTITUDE_CONTROL UNPACKING - - -/** - * @brief Get field target from attitude_control message - * - * @return The system to be controlled - */ -static inline uint8_t mavlink_msg_attitude_control_get_target(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field roll from attitude_control message - * - * @return roll - */ -static inline float mavlink_msg_attitude_control_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field pitch from attitude_control message - * - * @return pitch - */ -static inline float mavlink_msg_attitude_control_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field yaw from attitude_control message - * - * @return yaw - */ -static inline float mavlink_msg_attitude_control_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field thrust from attitude_control message - * - * @return thrust - */ -static inline float mavlink_msg_attitude_control_get_thrust(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field roll_manual from attitude_control message - * - * @return roll control enabled auto:0, manual:1 - */ -static inline uint8_t mavlink_msg_attitude_control_get_roll_manual(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field pitch_manual from attitude_control message - * - * @return pitch auto:0, manual:1 - */ -static inline uint8_t mavlink_msg_attitude_control_get_pitch_manual(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 18); -} - -/** - * @brief Get field yaw_manual from attitude_control message - * - * @return yaw auto:0, manual:1 - */ -static inline uint8_t mavlink_msg_attitude_control_get_yaw_manual(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 19); -} - -/** - * @brief Get field thrust_manual from attitude_control message - * - * @return thrust auto:0, manual:1 - */ -static inline uint8_t mavlink_msg_attitude_control_get_thrust_manual(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Decode a attitude_control message into a struct - * - * @param msg The message to decode - * @param attitude_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_attitude_control_decode(const mavlink_message_t* msg, mavlink_attitude_control_t* attitude_control) -{ -#if MAVLINK_NEED_BYTE_SWAP - attitude_control->roll = mavlink_msg_attitude_control_get_roll(msg); - attitude_control->pitch = mavlink_msg_attitude_control_get_pitch(msg); - attitude_control->yaw = mavlink_msg_attitude_control_get_yaw(msg); - attitude_control->thrust = mavlink_msg_attitude_control_get_thrust(msg); - attitude_control->target = mavlink_msg_attitude_control_get_target(msg); - attitude_control->roll_manual = mavlink_msg_attitude_control_get_roll_manual(msg); - attitude_control->pitch_manual = mavlink_msg_attitude_control_get_pitch_manual(msg); - attitude_control->yaw_manual = mavlink_msg_attitude_control_get_yaw_manual(msg); - attitude_control->thrust_manual = mavlink_msg_attitude_control_get_thrust_manual(msg); -#else - memcpy(attitude_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_CONTROL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h deleted file mode 100644 index 7bc27982a..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_brief_feature.h +++ /dev/null @@ -1,369 +0,0 @@ -// MESSAGE BRIEF_FEATURE PACKING - -#define MAVLINK_MSG_ID_BRIEF_FEATURE 195 - -typedef struct __mavlink_brief_feature_t -{ - float x; ///< x position in m - float y; ///< y position in m - float z; ///< z position in m - float response; ///< Harris operator response at this location - uint16_t size; ///< Size in pixels - uint16_t orientation; ///< Orientation - uint8_t orientation_assignment; ///< Orientation assignment 0: false, 1:true - uint8_t descriptor[32]; ///< Descriptor -} mavlink_brief_feature_t; - -#define MAVLINK_MSG_ID_BRIEF_FEATURE_LEN 53 -#define MAVLINK_MSG_ID_195_LEN 53 - -#define MAVLINK_MSG_ID_BRIEF_FEATURE_CRC 88 -#define MAVLINK_MSG_ID_195_CRC 88 - -#define MAVLINK_MSG_BRIEF_FEATURE_FIELD_DESCRIPTOR_LEN 32 - -#define MAVLINK_MESSAGE_INFO_BRIEF_FEATURE { \ - "BRIEF_FEATURE", \ - 8, \ - { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_brief_feature_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_brief_feature_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_brief_feature_t, z) }, \ - { "response", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_brief_feature_t, response) }, \ - { "size", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_brief_feature_t, size) }, \ - { "orientation", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_brief_feature_t, orientation) }, \ - { "orientation_assignment", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_brief_feature_t, orientation_assignment) }, \ - { "descriptor", NULL, MAVLINK_TYPE_UINT8_T, 32, 21, offsetof(mavlink_brief_feature_t, descriptor) }, \ - } \ -} - - -/** - * @brief Pack a brief_feature message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param x x position in m - * @param y y position in m - * @param z z position in m - * @param orientation_assignment Orientation assignment 0: false, 1:true - * @param size Size in pixels - * @param orientation Orientation - * @param descriptor Descriptor - * @param response Harris operator response at this location - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_brief_feature_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BRIEF_FEATURE_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, response); - _mav_put_uint16_t(buf, 16, size); - _mav_put_uint16_t(buf, 18, orientation); - _mav_put_uint8_t(buf, 20, orientation_assignment); - _mav_put_uint8_t_array(buf, 21, descriptor, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#else - mavlink_brief_feature_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.response = response; - packet.size = size; - packet.orientation = orientation; - packet.orientation_assignment = orientation_assignment; - mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#endif -} - -/** - * @brief Pack a brief_feature message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param x x position in m - * @param y y position in m - * @param z z position in m - * @param orientation_assignment Orientation assignment 0: false, 1:true - * @param size Size in pixels - * @param orientation Orientation - * @param descriptor Descriptor - * @param response Harris operator response at this location - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_brief_feature_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float x,float y,float z,uint8_t orientation_assignment,uint16_t size,uint16_t orientation,const uint8_t *descriptor,float response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BRIEF_FEATURE_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, response); - _mav_put_uint16_t(buf, 16, size); - _mav_put_uint16_t(buf, 18, orientation); - _mav_put_uint8_t(buf, 20, orientation_assignment); - _mav_put_uint8_t_array(buf, 21, descriptor, 32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#else - mavlink_brief_feature_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.response = response; - packet.size = size; - packet.orientation = orientation; - packet.orientation_assignment = orientation_assignment; - mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_BRIEF_FEATURE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#endif -} - -/** - * @brief Encode a brief_feature struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param brief_feature C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_brief_feature_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_brief_feature_t* brief_feature) -{ - return mavlink_msg_brief_feature_pack(system_id, component_id, msg, brief_feature->x, brief_feature->y, brief_feature->z, brief_feature->orientation_assignment, brief_feature->size, brief_feature->orientation, brief_feature->descriptor, brief_feature->response); -} - -/** - * @brief Encode a brief_feature struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param brief_feature C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_brief_feature_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_brief_feature_t* brief_feature) -{ - return mavlink_msg_brief_feature_pack_chan(system_id, component_id, chan, msg, brief_feature->x, brief_feature->y, brief_feature->z, brief_feature->orientation_assignment, brief_feature->size, brief_feature->orientation, brief_feature->descriptor, brief_feature->response); -} - -/** - * @brief Send a brief_feature message - * @param chan MAVLink channel to send the message - * - * @param x x position in m - * @param y y position in m - * @param z z position in m - * @param orientation_assignment Orientation assignment 0: false, 1:true - * @param size Size in pixels - * @param orientation Orientation - * @param descriptor Descriptor - * @param response Harris operator response at this location - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_brief_feature_send(mavlink_channel_t chan, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_BRIEF_FEATURE_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, response); - _mav_put_uint16_t(buf, 16, size); - _mav_put_uint16_t(buf, 18, orientation); - _mav_put_uint8_t(buf, 20, orientation_assignment); - _mav_put_uint8_t_array(buf, 21, descriptor, 32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#endif -#else - mavlink_brief_feature_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.response = response; - packet.size = size; - packet.orientation = orientation; - packet.orientation_assignment = orientation_assignment; - mav_array_memcpy(packet.descriptor, descriptor, sizeof(uint8_t)*32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)&packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)&packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_BRIEF_FEATURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_brief_feature_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float x, float y, float z, uint8_t orientation_assignment, uint16_t size, uint16_t orientation, const uint8_t *descriptor, float response) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, response); - _mav_put_uint16_t(buf, 16, size); - _mav_put_uint16_t(buf, 18, orientation); - _mav_put_uint8_t(buf, 20, orientation_assignment); - _mav_put_uint8_t_array(buf, 21, descriptor, 32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, buf, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#endif -#else - mavlink_brief_feature_t *packet = (mavlink_brief_feature_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->response = response; - packet->size = size; - packet->orientation = orientation; - packet->orientation_assignment = orientation_assignment; - mav_array_memcpy(packet->descriptor, descriptor, sizeof(uint8_t)*32); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN, MAVLINK_MSG_ID_BRIEF_FEATURE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BRIEF_FEATURE, (const char *)packet, MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE BRIEF_FEATURE UNPACKING - - -/** - * @brief Get field x from brief_feature message - * - * @return x position in m - */ -static inline float mavlink_msg_brief_feature_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field y from brief_feature message - * - * @return y position in m - */ -static inline float mavlink_msg_brief_feature_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field z from brief_feature message - * - * @return z position in m - */ -static inline float mavlink_msg_brief_feature_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field orientation_assignment from brief_feature message - * - * @return Orientation assignment 0: false, 1:true - */ -static inline uint8_t mavlink_msg_brief_feature_get_orientation_assignment(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 20); -} - -/** - * @brief Get field size from brief_feature message - * - * @return Size in pixels - */ -static inline uint16_t mavlink_msg_brief_feature_get_size(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field orientation from brief_feature message - * - * @return Orientation - */ -static inline uint16_t mavlink_msg_brief_feature_get_orientation(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 18); -} - -/** - * @brief Get field descriptor from brief_feature message - * - * @return Descriptor - */ -static inline uint16_t mavlink_msg_brief_feature_get_descriptor(const mavlink_message_t* msg, uint8_t *descriptor) -{ - return _MAV_RETURN_uint8_t_array(msg, descriptor, 32, 21); -} - -/** - * @brief Get field response from brief_feature message - * - * @return Harris operator response at this location - */ -static inline float mavlink_msg_brief_feature_get_response(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a brief_feature message into a struct - * - * @param msg The message to decode - * @param brief_feature C-struct to decode the message contents into - */ -static inline void mavlink_msg_brief_feature_decode(const mavlink_message_t* msg, mavlink_brief_feature_t* brief_feature) -{ -#if MAVLINK_NEED_BYTE_SWAP - brief_feature->x = mavlink_msg_brief_feature_get_x(msg); - brief_feature->y = mavlink_msg_brief_feature_get_y(msg); - brief_feature->z = mavlink_msg_brief_feature_get_z(msg); - brief_feature->response = mavlink_msg_brief_feature_get_response(msg); - brief_feature->size = mavlink_msg_brief_feature_get_size(msg); - brief_feature->orientation = mavlink_msg_brief_feature_get_orientation(msg); - brief_feature->orientation_assignment = mavlink_msg_brief_feature_get_orientation_assignment(msg); - mavlink_msg_brief_feature_get_descriptor(msg, brief_feature->descriptor); -#else - memcpy(brief_feature, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BRIEF_FEATURE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h deleted file mode 100644 index 37270d49c..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_available.h +++ /dev/null @@ -1,737 +0,0 @@ -// MESSAGE IMAGE_AVAILABLE PACKING - -#define MAVLINK_MSG_ID_IMAGE_AVAILABLE 154 - -typedef struct __mavlink_image_available_t -{ - uint64_t cam_id; ///< Camera id - uint64_t timestamp; ///< Timestamp - uint64_t valid_until; ///< Until which timestamp this buffer will stay valid - uint32_t img_seq; ///< The image sequence number - uint32_t img_buf_index; ///< Position of the image in the buffer, starts with 0 - uint32_t key; ///< Shared memory area key - uint32_t exposure; ///< Exposure time, in microseconds - float gain; ///< Camera gain - float roll; ///< Roll angle in rad - float pitch; ///< Pitch angle in rad - float yaw; ///< Yaw angle in rad - float local_z; ///< Local frame Z coordinate (height over ground) - float lat; ///< GPS X coordinate - float lon; ///< GPS Y coordinate - float alt; ///< Global frame altitude - float ground_x; ///< Ground truth X - float ground_y; ///< Ground truth Y - float ground_z; ///< Ground truth Z - uint16_t width; ///< Image width - uint16_t height; ///< Image height - uint16_t depth; ///< Image depth - uint8_t cam_no; ///< Camera # (starts with 0) - uint8_t channels; ///< Image channels -} mavlink_image_available_t; - -#define MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN 92 -#define MAVLINK_MSG_ID_154_LEN 92 - -#define MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC 224 -#define MAVLINK_MSG_ID_154_CRC 224 - - - -#define MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE { \ - "IMAGE_AVAILABLE", \ - 23, \ - { { "cam_id", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_image_available_t, cam_id) }, \ - { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_image_available_t, timestamp) }, \ - { "valid_until", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_image_available_t, valid_until) }, \ - { "img_seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_image_available_t, img_seq) }, \ - { "img_buf_index", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_image_available_t, img_buf_index) }, \ - { "key", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_image_available_t, key) }, \ - { "exposure", NULL, MAVLINK_TYPE_UINT32_T, 0, 36, offsetof(mavlink_image_available_t, exposure) }, \ - { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_image_available_t, gain) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_image_available_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_image_available_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_image_available_t, yaw) }, \ - { "local_z", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_image_available_t, local_z) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_image_available_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 64, offsetof(mavlink_image_available_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 68, offsetof(mavlink_image_available_t, alt) }, \ - { "ground_x", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_image_available_t, ground_x) }, \ - { "ground_y", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_image_available_t, ground_y) }, \ - { "ground_z", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_image_available_t, ground_z) }, \ - { "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 84, offsetof(mavlink_image_available_t, width) }, \ - { "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 86, offsetof(mavlink_image_available_t, height) }, \ - { "depth", NULL, MAVLINK_TYPE_UINT16_T, 0, 88, offsetof(mavlink_image_available_t, depth) }, \ - { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 90, offsetof(mavlink_image_available_t, cam_no) }, \ - { "channels", NULL, MAVLINK_TYPE_UINT8_T, 0, 91, offsetof(mavlink_image_available_t, channels) }, \ - } \ -} - - -/** - * @brief Pack a image_available message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param cam_id Camera id - * @param cam_no Camera # (starts with 0) - * @param timestamp Timestamp - * @param valid_until Until which timestamp this buffer will stay valid - * @param img_seq The image sequence number - * @param img_buf_index Position of the image in the buffer, starts with 0 - * @param width Image width - * @param height Image height - * @param depth Image depth - * @param channels Image channels - * @param key Shared memory area key - * @param exposure Exposure time, in microseconds - * @param gain Camera gain - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @param local_z Local frame Z coordinate (height over ground) - * @param lat GPS X coordinate - * @param lon GPS Y coordinate - * @param alt Global frame altitude - * @param ground_x Ground truth X - * @param ground_y Ground truth Y - * @param ground_z Ground truth Z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_image_available_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN]; - _mav_put_uint64_t(buf, 0, cam_id); - _mav_put_uint64_t(buf, 8, timestamp); - _mav_put_uint64_t(buf, 16, valid_until); - _mav_put_uint32_t(buf, 24, img_seq); - _mav_put_uint32_t(buf, 28, img_buf_index); - _mav_put_uint32_t(buf, 32, key); - _mav_put_uint32_t(buf, 36, exposure); - _mav_put_float(buf, 40, gain); - _mav_put_float(buf, 44, roll); - _mav_put_float(buf, 48, pitch); - _mav_put_float(buf, 52, yaw); - _mav_put_float(buf, 56, local_z); - _mav_put_float(buf, 60, lat); - _mav_put_float(buf, 64, lon); - _mav_put_float(buf, 68, alt); - _mav_put_float(buf, 72, ground_x); - _mav_put_float(buf, 76, ground_y); - _mav_put_float(buf, 80, ground_z); - _mav_put_uint16_t(buf, 84, width); - _mav_put_uint16_t(buf, 86, height); - _mav_put_uint16_t(buf, 88, depth); - _mav_put_uint8_t(buf, 90, cam_no); - _mav_put_uint8_t(buf, 91, channels); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#else - mavlink_image_available_t packet; - packet.cam_id = cam_id; - packet.timestamp = timestamp; - packet.valid_until = valid_until; - packet.img_seq = img_seq; - packet.img_buf_index = img_buf_index; - packet.key = key; - packet.exposure = exposure; - packet.gain = gain; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.local_z = local_z; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.ground_x = ground_x; - packet.ground_y = ground_y; - packet.ground_z = ground_z; - packet.width = width; - packet.height = height; - packet.depth = depth; - packet.cam_no = cam_no; - packet.channels = channels; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#endif -} - -/** - * @brief Pack a image_available message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param cam_id Camera id - * @param cam_no Camera # (starts with 0) - * @param timestamp Timestamp - * @param valid_until Until which timestamp this buffer will stay valid - * @param img_seq The image sequence number - * @param img_buf_index Position of the image in the buffer, starts with 0 - * @param width Image width - * @param height Image height - * @param depth Image depth - * @param channels Image channels - * @param key Shared memory area key - * @param exposure Exposure time, in microseconds - * @param gain Camera gain - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @param local_z Local frame Z coordinate (height over ground) - * @param lat GPS X coordinate - * @param lon GPS Y coordinate - * @param alt Global frame altitude - * @param ground_x Ground truth X - * @param ground_y Ground truth Y - * @param ground_z Ground truth Z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_image_available_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t cam_id,uint8_t cam_no,uint64_t timestamp,uint64_t valid_until,uint32_t img_seq,uint32_t img_buf_index,uint16_t width,uint16_t height,uint16_t depth,uint8_t channels,uint32_t key,uint32_t exposure,float gain,float roll,float pitch,float yaw,float local_z,float lat,float lon,float alt,float ground_x,float ground_y,float ground_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN]; - _mav_put_uint64_t(buf, 0, cam_id); - _mav_put_uint64_t(buf, 8, timestamp); - _mav_put_uint64_t(buf, 16, valid_until); - _mav_put_uint32_t(buf, 24, img_seq); - _mav_put_uint32_t(buf, 28, img_buf_index); - _mav_put_uint32_t(buf, 32, key); - _mav_put_uint32_t(buf, 36, exposure); - _mav_put_float(buf, 40, gain); - _mav_put_float(buf, 44, roll); - _mav_put_float(buf, 48, pitch); - _mav_put_float(buf, 52, yaw); - _mav_put_float(buf, 56, local_z); - _mav_put_float(buf, 60, lat); - _mav_put_float(buf, 64, lon); - _mav_put_float(buf, 68, alt); - _mav_put_float(buf, 72, ground_x); - _mav_put_float(buf, 76, ground_y); - _mav_put_float(buf, 80, ground_z); - _mav_put_uint16_t(buf, 84, width); - _mav_put_uint16_t(buf, 86, height); - _mav_put_uint16_t(buf, 88, depth); - _mav_put_uint8_t(buf, 90, cam_no); - _mav_put_uint8_t(buf, 91, channels); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#else - mavlink_image_available_t packet; - packet.cam_id = cam_id; - packet.timestamp = timestamp; - packet.valid_until = valid_until; - packet.img_seq = img_seq; - packet.img_buf_index = img_buf_index; - packet.key = key; - packet.exposure = exposure; - packet.gain = gain; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.local_z = local_z; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.ground_x = ground_x; - packet.ground_y = ground_y; - packet.ground_z = ground_z; - packet.width = width; - packet.height = height; - packet.depth = depth; - packet.cam_no = cam_no; - packet.channels = channels; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_IMAGE_AVAILABLE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#endif -} - -/** - * @brief Encode a image_available struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param image_available C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_image_available_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_available_t* image_available) -{ - return mavlink_msg_image_available_pack(system_id, component_id, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt, image_available->ground_x, image_available->ground_y, image_available->ground_z); -} - -/** - * @brief Encode a image_available struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param image_available C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_image_available_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_image_available_t* image_available) -{ - return mavlink_msg_image_available_pack_chan(system_id, component_id, chan, msg, image_available->cam_id, image_available->cam_no, image_available->timestamp, image_available->valid_until, image_available->img_seq, image_available->img_buf_index, image_available->width, image_available->height, image_available->depth, image_available->channels, image_available->key, image_available->exposure, image_available->gain, image_available->roll, image_available->pitch, image_available->yaw, image_available->local_z, image_available->lat, image_available->lon, image_available->alt, image_available->ground_x, image_available->ground_y, image_available->ground_z); -} - -/** - * @brief Send a image_available message - * @param chan MAVLink channel to send the message - * - * @param cam_id Camera id - * @param cam_no Camera # (starts with 0) - * @param timestamp Timestamp - * @param valid_until Until which timestamp this buffer will stay valid - * @param img_seq The image sequence number - * @param img_buf_index Position of the image in the buffer, starts with 0 - * @param width Image width - * @param height Image height - * @param depth Image depth - * @param channels Image channels - * @param key Shared memory area key - * @param exposure Exposure time, in microseconds - * @param gain Camera gain - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @param local_z Local frame Z coordinate (height over ground) - * @param lat GPS X coordinate - * @param lon GPS Y coordinate - * @param alt Global frame altitude - * @param ground_x Ground truth X - * @param ground_y Ground truth Y - * @param ground_z Ground truth Z - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_image_available_send(mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN]; - _mav_put_uint64_t(buf, 0, cam_id); - _mav_put_uint64_t(buf, 8, timestamp); - _mav_put_uint64_t(buf, 16, valid_until); - _mav_put_uint32_t(buf, 24, img_seq); - _mav_put_uint32_t(buf, 28, img_buf_index); - _mav_put_uint32_t(buf, 32, key); - _mav_put_uint32_t(buf, 36, exposure); - _mav_put_float(buf, 40, gain); - _mav_put_float(buf, 44, roll); - _mav_put_float(buf, 48, pitch); - _mav_put_float(buf, 52, yaw); - _mav_put_float(buf, 56, local_z); - _mav_put_float(buf, 60, lat); - _mav_put_float(buf, 64, lon); - _mav_put_float(buf, 68, alt); - _mav_put_float(buf, 72, ground_x); - _mav_put_float(buf, 76, ground_y); - _mav_put_float(buf, 80, ground_z); - _mav_put_uint16_t(buf, 84, width); - _mav_put_uint16_t(buf, 86, height); - _mav_put_uint16_t(buf, 88, depth); - _mav_put_uint8_t(buf, 90, cam_no); - _mav_put_uint8_t(buf, 91, channels); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#endif -#else - mavlink_image_available_t packet; - packet.cam_id = cam_id; - packet.timestamp = timestamp; - packet.valid_until = valid_until; - packet.img_seq = img_seq; - packet.img_buf_index = img_buf_index; - packet.key = key; - packet.exposure = exposure; - packet.gain = gain; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.local_z = local_z; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.ground_x = ground_x; - packet.ground_y = ground_y; - packet.ground_z = ground_z; - packet.width = width; - packet.height = height; - packet.depth = depth; - packet.cam_no = cam_no; - packet.channels = channels; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_image_available_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t cam_id, uint8_t cam_no, uint64_t timestamp, uint64_t valid_until, uint32_t img_seq, uint32_t img_buf_index, uint16_t width, uint16_t height, uint16_t depth, uint8_t channels, uint32_t key, uint32_t exposure, float gain, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, cam_id); - _mav_put_uint64_t(buf, 8, timestamp); - _mav_put_uint64_t(buf, 16, valid_until); - _mav_put_uint32_t(buf, 24, img_seq); - _mav_put_uint32_t(buf, 28, img_buf_index); - _mav_put_uint32_t(buf, 32, key); - _mav_put_uint32_t(buf, 36, exposure); - _mav_put_float(buf, 40, gain); - _mav_put_float(buf, 44, roll); - _mav_put_float(buf, 48, pitch); - _mav_put_float(buf, 52, yaw); - _mav_put_float(buf, 56, local_z); - _mav_put_float(buf, 60, lat); - _mav_put_float(buf, 64, lon); - _mav_put_float(buf, 68, alt); - _mav_put_float(buf, 72, ground_x); - _mav_put_float(buf, 76, ground_y); - _mav_put_float(buf, 80, ground_z); - _mav_put_uint16_t(buf, 84, width); - _mav_put_uint16_t(buf, 86, height); - _mav_put_uint16_t(buf, 88, depth); - _mav_put_uint8_t(buf, 90, cam_no); - _mav_put_uint8_t(buf, 91, channels); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, buf, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#endif -#else - mavlink_image_available_t *packet = (mavlink_image_available_t *)msgbuf; - packet->cam_id = cam_id; - packet->timestamp = timestamp; - packet->valid_until = valid_until; - packet->img_seq = img_seq; - packet->img_buf_index = img_buf_index; - packet->key = key; - packet->exposure = exposure; - packet->gain = gain; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->local_z = local_z; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->ground_x = ground_x; - packet->ground_y = ground_y; - packet->ground_z = ground_z; - packet->width = width; - packet->height = height; - packet->depth = depth; - packet->cam_no = cam_no; - packet->channels = channels; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN, MAVLINK_MSG_ID_IMAGE_AVAILABLE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_AVAILABLE, (const char *)packet, MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE IMAGE_AVAILABLE UNPACKING - - -/** - * @brief Get field cam_id from image_available message - * - * @return Camera id - */ -static inline uint64_t mavlink_msg_image_available_get_cam_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field cam_no from image_available message - * - * @return Camera # (starts with 0) - */ -static inline uint8_t mavlink_msg_image_available_get_cam_no(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 90); -} - -/** - * @brief Get field timestamp from image_available message - * - * @return Timestamp - */ -static inline uint64_t mavlink_msg_image_available_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 8); -} - -/** - * @brief Get field valid_until from image_available message - * - * @return Until which timestamp this buffer will stay valid - */ -static inline uint64_t mavlink_msg_image_available_get_valid_until(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 16); -} - -/** - * @brief Get field img_seq from image_available message - * - * @return The image sequence number - */ -static inline uint32_t mavlink_msg_image_available_get_img_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 24); -} - -/** - * @brief Get field img_buf_index from image_available message - * - * @return Position of the image in the buffer, starts with 0 - */ -static inline uint32_t mavlink_msg_image_available_get_img_buf_index(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 28); -} - -/** - * @brief Get field width from image_available message - * - * @return Image width - */ -static inline uint16_t mavlink_msg_image_available_get_width(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 84); -} - -/** - * @brief Get field height from image_available message - * - * @return Image height - */ -static inline uint16_t mavlink_msg_image_available_get_height(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 86); -} - -/** - * @brief Get field depth from image_available message - * - * @return Image depth - */ -static inline uint16_t mavlink_msg_image_available_get_depth(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 88); -} - -/** - * @brief Get field channels from image_available message - * - * @return Image channels - */ -static inline uint8_t mavlink_msg_image_available_get_channels(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 91); -} - -/** - * @brief Get field key from image_available message - * - * @return Shared memory area key - */ -static inline uint32_t mavlink_msg_image_available_get_key(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 32); -} - -/** - * @brief Get field exposure from image_available message - * - * @return Exposure time, in microseconds - */ -static inline uint32_t mavlink_msg_image_available_get_exposure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 36); -} - -/** - * @brief Get field gain from image_available message - * - * @return Camera gain - */ -static inline float mavlink_msg_image_available_get_gain(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field roll from image_available message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_image_available_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field pitch from image_available message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_image_available_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Get field yaw from image_available message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_image_available_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 52); -} - -/** - * @brief Get field local_z from image_available message - * - * @return Local frame Z coordinate (height over ground) - */ -static inline float mavlink_msg_image_available_get_local_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 56); -} - -/** - * @brief Get field lat from image_available message - * - * @return GPS X coordinate - */ -static inline float mavlink_msg_image_available_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 60); -} - -/** - * @brief Get field lon from image_available message - * - * @return GPS Y coordinate - */ -static inline float mavlink_msg_image_available_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 64); -} - -/** - * @brief Get field alt from image_available message - * - * @return Global frame altitude - */ -static inline float mavlink_msg_image_available_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 68); -} - -/** - * @brief Get field ground_x from image_available message - * - * @return Ground truth X - */ -static inline float mavlink_msg_image_available_get_ground_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 72); -} - -/** - * @brief Get field ground_y from image_available message - * - * @return Ground truth Y - */ -static inline float mavlink_msg_image_available_get_ground_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 76); -} - -/** - * @brief Get field ground_z from image_available message - * - * @return Ground truth Z - */ -static inline float mavlink_msg_image_available_get_ground_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 80); -} - -/** - * @brief Decode a image_available message into a struct - * - * @param msg The message to decode - * @param image_available C-struct to decode the message contents into - */ -static inline void mavlink_msg_image_available_decode(const mavlink_message_t* msg, mavlink_image_available_t* image_available) -{ -#if MAVLINK_NEED_BYTE_SWAP - image_available->cam_id = mavlink_msg_image_available_get_cam_id(msg); - image_available->timestamp = mavlink_msg_image_available_get_timestamp(msg); - image_available->valid_until = mavlink_msg_image_available_get_valid_until(msg); - image_available->img_seq = mavlink_msg_image_available_get_img_seq(msg); - image_available->img_buf_index = mavlink_msg_image_available_get_img_buf_index(msg); - image_available->key = mavlink_msg_image_available_get_key(msg); - image_available->exposure = mavlink_msg_image_available_get_exposure(msg); - image_available->gain = mavlink_msg_image_available_get_gain(msg); - image_available->roll = mavlink_msg_image_available_get_roll(msg); - image_available->pitch = mavlink_msg_image_available_get_pitch(msg); - image_available->yaw = mavlink_msg_image_available_get_yaw(msg); - image_available->local_z = mavlink_msg_image_available_get_local_z(msg); - image_available->lat = mavlink_msg_image_available_get_lat(msg); - image_available->lon = mavlink_msg_image_available_get_lon(msg); - image_available->alt = mavlink_msg_image_available_get_alt(msg); - image_available->ground_x = mavlink_msg_image_available_get_ground_x(msg); - image_available->ground_y = mavlink_msg_image_available_get_ground_y(msg); - image_available->ground_z = mavlink_msg_image_available_get_ground_z(msg); - image_available->width = mavlink_msg_image_available_get_width(msg); - image_available->height = mavlink_msg_image_available_get_height(msg); - image_available->depth = mavlink_msg_image_available_get_depth(msg); - image_available->cam_no = mavlink_msg_image_available_get_cam_no(msg); - image_available->channels = mavlink_msg_image_available_get_channels(msg); -#else - memcpy(image_available, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_IMAGE_AVAILABLE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h deleted file mode 100644 index 85f8eff55..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_trigger_control.h +++ /dev/null @@ -1,209 +0,0 @@ -// MESSAGE IMAGE_TRIGGER_CONTROL PACKING - -#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL 153 - -typedef struct __mavlink_image_trigger_control_t -{ - uint8_t enable; ///< 0 to disable, 1 to enable -} mavlink_image_trigger_control_t; - -#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN 1 -#define MAVLINK_MSG_ID_153_LEN 1 - -#define MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC 95 -#define MAVLINK_MSG_ID_153_CRC 95 - - - -#define MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL { \ - "IMAGE_TRIGGER_CONTROL", \ - 1, \ - { { "enable", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_image_trigger_control_t, enable) }, \ - } \ -} - - -/** - * @brief Pack a image_trigger_control message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param enable 0 to disable, 1 to enable - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_image_trigger_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t enable) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, enable); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#else - mavlink_image_trigger_control_t packet; - packet.enable = enable; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#endif -} - -/** - * @brief Pack a image_trigger_control message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param enable 0 to disable, 1 to enable - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_image_trigger_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t enable) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, enable); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#else - mavlink_image_trigger_control_t packet; - packet.enable = enable; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#endif -} - -/** - * @brief Encode a image_trigger_control struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param image_trigger_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_image_trigger_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control) -{ - return mavlink_msg_image_trigger_control_pack(system_id, component_id, msg, image_trigger_control->enable); -} - -/** - * @brief Encode a image_trigger_control struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param image_trigger_control C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_image_trigger_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_image_trigger_control_t* image_trigger_control) -{ - return mavlink_msg_image_trigger_control_pack_chan(system_id, component_id, chan, msg, image_trigger_control->enable); -} - -/** - * @brief Send a image_trigger_control message - * @param chan MAVLink channel to send the message - * - * @param enable 0 to disable, 1 to enable - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_image_trigger_control_send(mavlink_channel_t chan, uint8_t enable) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN]; - _mav_put_uint8_t(buf, 0, enable); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#endif -#else - mavlink_image_trigger_control_t packet; - packet.enable = enable; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_image_trigger_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t enable) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, enable); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, buf, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#endif -#else - mavlink_image_trigger_control_t *packet = (mavlink_image_trigger_control_t *)msgbuf; - packet->enable = enable; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL, (const char *)packet, MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE IMAGE_TRIGGER_CONTROL UNPACKING - - -/** - * @brief Get field enable from image_trigger_control message - * - * @return 0 to disable, 1 to enable - */ -static inline uint8_t mavlink_msg_image_trigger_control_get_enable(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Decode a image_trigger_control message into a struct - * - * @param msg The message to decode - * @param image_trigger_control C-struct to decode the message contents into - */ -static inline void mavlink_msg_image_trigger_control_decode(const mavlink_message_t* msg, mavlink_image_trigger_control_t* image_trigger_control) -{ -#if MAVLINK_NEED_BYTE_SWAP - image_trigger_control->enable = mavlink_msg_image_trigger_control_get_enable(msg); -#else - memcpy(image_trigger_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_IMAGE_TRIGGER_CONTROL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h deleted file mode 100644 index b438c74ea..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_image_triggered.h +++ /dev/null @@ -1,473 +0,0 @@ -// MESSAGE IMAGE_TRIGGERED PACKING - -#define MAVLINK_MSG_ID_IMAGE_TRIGGERED 152 - -typedef struct __mavlink_image_triggered_t -{ - uint64_t timestamp; ///< Timestamp - uint32_t seq; ///< IMU seq - float roll; ///< Roll angle in rad - float pitch; ///< Pitch angle in rad - float yaw; ///< Yaw angle in rad - float local_z; ///< Local frame Z coordinate (height over ground) - float lat; ///< GPS X coordinate - float lon; ///< GPS Y coordinate - float alt; ///< Global frame altitude - float ground_x; ///< Ground truth X - float ground_y; ///< Ground truth Y - float ground_z; ///< Ground truth Z -} mavlink_image_triggered_t; - -#define MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN 52 -#define MAVLINK_MSG_ID_152_LEN 52 - -#define MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC 86 -#define MAVLINK_MSG_ID_152_CRC 86 - - - -#define MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED { \ - "IMAGE_TRIGGERED", \ - 12, \ - { { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_image_triggered_t, timestamp) }, \ - { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_image_triggered_t, seq) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_image_triggered_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_image_triggered_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_image_triggered_t, yaw) }, \ - { "local_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_image_triggered_t, local_z) }, \ - { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_image_triggered_t, lat) }, \ - { "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_image_triggered_t, lon) }, \ - { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_image_triggered_t, alt) }, \ - { "ground_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_image_triggered_t, ground_x) }, \ - { "ground_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_image_triggered_t, ground_y) }, \ - { "ground_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_image_triggered_t, ground_z) }, \ - } \ -} - - -/** - * @brief Pack a image_triggered message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param timestamp Timestamp - * @param seq IMU seq - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @param local_z Local frame Z coordinate (height over ground) - * @param lat GPS X coordinate - * @param lon GPS Y coordinate - * @param alt Global frame altitude - * @param ground_x Ground truth X - * @param ground_y Ground truth Y - * @param ground_z Ground truth Z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_image_triggered_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_float(buf, 12, roll); - _mav_put_float(buf, 16, pitch); - _mav_put_float(buf, 20, yaw); - _mav_put_float(buf, 24, local_z); - _mav_put_float(buf, 28, lat); - _mav_put_float(buf, 32, lon); - _mav_put_float(buf, 36, alt); - _mav_put_float(buf, 40, ground_x); - _mav_put_float(buf, 44, ground_y); - _mav_put_float(buf, 48, ground_z); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#else - mavlink_image_triggered_t packet; - packet.timestamp = timestamp; - packet.seq = seq; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.local_z = local_z; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.ground_x = ground_x; - packet.ground_y = ground_y; - packet.ground_z = ground_z; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#endif -} - -/** - * @brief Pack a image_triggered message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param timestamp Timestamp - * @param seq IMU seq - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @param local_z Local frame Z coordinate (height over ground) - * @param lat GPS X coordinate - * @param lon GPS Y coordinate - * @param alt Global frame altitude - * @param ground_x Ground truth X - * @param ground_y Ground truth Y - * @param ground_z Ground truth Z - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_image_triggered_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint64_t timestamp,uint32_t seq,float roll,float pitch,float yaw,float local_z,float lat,float lon,float alt,float ground_x,float ground_y,float ground_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_float(buf, 12, roll); - _mav_put_float(buf, 16, pitch); - _mav_put_float(buf, 20, yaw); - _mav_put_float(buf, 24, local_z); - _mav_put_float(buf, 28, lat); - _mav_put_float(buf, 32, lon); - _mav_put_float(buf, 36, alt); - _mav_put_float(buf, 40, ground_x); - _mav_put_float(buf, 44, ground_y); - _mav_put_float(buf, 48, ground_z); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#else - mavlink_image_triggered_t packet; - packet.timestamp = timestamp; - packet.seq = seq; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.local_z = local_z; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.ground_x = ground_x; - packet.ground_y = ground_y; - packet.ground_z = ground_z; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_IMAGE_TRIGGERED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#endif -} - -/** - * @brief Encode a image_triggered struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param image_triggered C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_image_triggered_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered) -{ - return mavlink_msg_image_triggered_pack(system_id, component_id, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z); -} - -/** - * @brief Encode a image_triggered struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param image_triggered C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_image_triggered_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_image_triggered_t* image_triggered) -{ - return mavlink_msg_image_triggered_pack_chan(system_id, component_id, chan, msg, image_triggered->timestamp, image_triggered->seq, image_triggered->roll, image_triggered->pitch, image_triggered->yaw, image_triggered->local_z, image_triggered->lat, image_triggered->lon, image_triggered->alt, image_triggered->ground_x, image_triggered->ground_y, image_triggered->ground_z); -} - -/** - * @brief Send a image_triggered message - * @param chan MAVLink channel to send the message - * - * @param timestamp Timestamp - * @param seq IMU seq - * @param roll Roll angle in rad - * @param pitch Pitch angle in rad - * @param yaw Yaw angle in rad - * @param local_z Local frame Z coordinate (height over ground) - * @param lat GPS X coordinate - * @param lon GPS Y coordinate - * @param alt Global frame altitude - * @param ground_x Ground truth X - * @param ground_y Ground truth Y - * @param ground_z Ground truth Z - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_image_triggered_send(mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN]; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_float(buf, 12, roll); - _mav_put_float(buf, 16, pitch); - _mav_put_float(buf, 20, yaw); - _mav_put_float(buf, 24, local_z); - _mav_put_float(buf, 28, lat); - _mav_put_float(buf, 32, lon); - _mav_put_float(buf, 36, alt); - _mav_put_float(buf, 40, ground_x); - _mav_put_float(buf, 44, ground_y); - _mav_put_float(buf, 48, ground_z); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#endif -#else - mavlink_image_triggered_t packet; - packet.timestamp = timestamp; - packet.seq = seq; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.local_z = local_z; - packet.lat = lat; - packet.lon = lon; - packet.alt = alt; - packet.ground_x = ground_x; - packet.ground_y = ground_y; - packet.ground_z = ground_z; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)&packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_image_triggered_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint32_t seq, float roll, float pitch, float yaw, float local_z, float lat, float lon, float alt, float ground_x, float ground_y, float ground_z) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint64_t(buf, 0, timestamp); - _mav_put_uint32_t(buf, 8, seq); - _mav_put_float(buf, 12, roll); - _mav_put_float(buf, 16, pitch); - _mav_put_float(buf, 20, yaw); - _mav_put_float(buf, 24, local_z); - _mav_put_float(buf, 28, lat); - _mav_put_float(buf, 32, lon); - _mav_put_float(buf, 36, alt); - _mav_put_float(buf, 40, ground_x); - _mav_put_float(buf, 44, ground_y); - _mav_put_float(buf, 48, ground_z); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, buf, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#endif -#else - mavlink_image_triggered_t *packet = (mavlink_image_triggered_t *)msgbuf; - packet->timestamp = timestamp; - packet->seq = seq; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->local_z = local_z; - packet->lat = lat; - packet->lon = lon; - packet->alt = alt; - packet->ground_x = ground_x; - packet->ground_y = ground_y; - packet->ground_z = ground_z; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN, MAVLINK_MSG_ID_IMAGE_TRIGGERED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_IMAGE_TRIGGERED, (const char *)packet, MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE IMAGE_TRIGGERED UNPACKING - - -/** - * @brief Get field timestamp from image_triggered message - * - * @return Timestamp - */ -static inline uint64_t mavlink_msg_image_triggered_get_timestamp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field seq from image_triggered message - * - * @return IMU seq - */ -static inline uint32_t mavlink_msg_image_triggered_get_seq(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 8); -} - -/** - * @brief Get field roll from image_triggered message - * - * @return Roll angle in rad - */ -static inline float mavlink_msg_image_triggered_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pitch from image_triggered message - * - * @return Pitch angle in rad - */ -static inline float mavlink_msg_image_triggered_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field yaw from image_triggered message - * - * @return Yaw angle in rad - */ -static inline float mavlink_msg_image_triggered_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field local_z from image_triggered message - * - * @return Local frame Z coordinate (height over ground) - */ -static inline float mavlink_msg_image_triggered_get_local_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 24); -} - -/** - * @brief Get field lat from image_triggered message - * - * @return GPS X coordinate - */ -static inline float mavlink_msg_image_triggered_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 28); -} - -/** - * @brief Get field lon from image_triggered message - * - * @return GPS Y coordinate - */ -static inline float mavlink_msg_image_triggered_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 32); -} - -/** - * @brief Get field alt from image_triggered message - * - * @return Global frame altitude - */ -static inline float mavlink_msg_image_triggered_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 36); -} - -/** - * @brief Get field ground_x from image_triggered message - * - * @return Ground truth X - */ -static inline float mavlink_msg_image_triggered_get_ground_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 40); -} - -/** - * @brief Get field ground_y from image_triggered message - * - * @return Ground truth Y - */ -static inline float mavlink_msg_image_triggered_get_ground_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 44); -} - -/** - * @brief Get field ground_z from image_triggered message - * - * @return Ground truth Z - */ -static inline float mavlink_msg_image_triggered_get_ground_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 48); -} - -/** - * @brief Decode a image_triggered message into a struct - * - * @param msg The message to decode - * @param image_triggered C-struct to decode the message contents into - */ -static inline void mavlink_msg_image_triggered_decode(const mavlink_message_t* msg, mavlink_image_triggered_t* image_triggered) -{ -#if MAVLINK_NEED_BYTE_SWAP - image_triggered->timestamp = mavlink_msg_image_triggered_get_timestamp(msg); - image_triggered->seq = mavlink_msg_image_triggered_get_seq(msg); - image_triggered->roll = mavlink_msg_image_triggered_get_roll(msg); - image_triggered->pitch = mavlink_msg_image_triggered_get_pitch(msg); - image_triggered->yaw = mavlink_msg_image_triggered_get_yaw(msg); - image_triggered->local_z = mavlink_msg_image_triggered_get_local_z(msg); - image_triggered->lat = mavlink_msg_image_triggered_get_lat(msg); - image_triggered->lon = mavlink_msg_image_triggered_get_lon(msg); - image_triggered->alt = mavlink_msg_image_triggered_get_alt(msg); - image_triggered->ground_x = mavlink_msg_image_triggered_get_ground_x(msg); - image_triggered->ground_y = mavlink_msg_image_triggered_get_ground_y(msg); - image_triggered->ground_z = mavlink_msg_image_triggered_get_ground_z(msg); -#else - memcpy(image_triggered, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_IMAGE_TRIGGERED_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h deleted file mode 100644 index 05452637e..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_marker.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE MARKER PACKING - -#define MAVLINK_MSG_ID_MARKER 171 - -typedef struct __mavlink_marker_t -{ - float x; ///< x position - float y; ///< y position - float z; ///< z position - float roll; ///< roll orientation - float pitch; ///< pitch orientation - float yaw; ///< yaw orientation - uint16_t id; ///< ID -} mavlink_marker_t; - -#define MAVLINK_MSG_ID_MARKER_LEN 26 -#define MAVLINK_MSG_ID_171_LEN 26 - -#define MAVLINK_MSG_ID_MARKER_CRC 249 -#define MAVLINK_MSG_ID_171_CRC 249 - - - -#define MAVLINK_MESSAGE_INFO_MARKER { \ - "MARKER", \ - 7, \ - { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_marker_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_marker_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_marker_t, z) }, \ - { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_marker_t, roll) }, \ - { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_marker_t, pitch) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_marker_t, yaw) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_marker_t, id) }, \ - } \ -} - - -/** - * @brief Pack a marker message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param id ID - * @param x x position - * @param y y position - * @param z z position - * @param roll roll orientation - * @param pitch pitch orientation - * @param yaw yaw orientation - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_marker_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MARKER_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, roll); - _mav_put_float(buf, 16, pitch); - _mav_put_float(buf, 20, yaw); - _mav_put_uint16_t(buf, 24, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MARKER_LEN); -#else - mavlink_marker_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MARKER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MARKER; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MARKER_LEN); -#endif -} - -/** - * @brief Pack a marker message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id ID - * @param x x position - * @param y y position - * @param z z position - * @param roll roll orientation - * @param pitch pitch orientation - * @param yaw yaw orientation - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_marker_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,float x,float y,float z,float roll,float pitch,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MARKER_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, roll); - _mav_put_float(buf, 16, pitch); - _mav_put_float(buf, 20, yaw); - _mav_put_uint16_t(buf, 24, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MARKER_LEN); -#else - mavlink_marker_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MARKER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_MARKER; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MARKER_LEN); -#endif -} - -/** - * @brief Encode a marker struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param marker C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_marker_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_marker_t* marker) -{ - return mavlink_msg_marker_pack(system_id, component_id, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw); -} - -/** - * @brief Encode a marker struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param marker C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_marker_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_marker_t* marker) -{ - return mavlink_msg_marker_pack_chan(system_id, component_id, chan, msg, marker->id, marker->x, marker->y, marker->z, marker->roll, marker->pitch, marker->yaw); -} - -/** - * @brief Send a marker message - * @param chan MAVLink channel to send the message - * - * @param id ID - * @param x x position - * @param y y position - * @param z z position - * @param roll roll orientation - * @param pitch pitch orientation - * @param yaw yaw orientation - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_marker_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_MARKER_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, roll); - _mav_put_float(buf, 16, pitch); - _mav_put_float(buf, 20, yaw); - _mav_put_uint16_t(buf, 24, id); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, MAVLINK_MSG_ID_MARKER_LEN); -#endif -#else - mavlink_marker_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.roll = roll; - packet.pitch = pitch; - packet.yaw = yaw; - packet.id = id; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)&packet, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)&packet, MAVLINK_MSG_ID_MARKER_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_MARKER_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_marker_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, float x, float y, float z, float roll, float pitch, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, roll); - _mav_put_float(buf, 16, pitch); - _mav_put_float(buf, 20, yaw); - _mav_put_uint16_t(buf, 24, id); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, buf, MAVLINK_MSG_ID_MARKER_LEN); -#endif -#else - mavlink_marker_t *packet = (mavlink_marker_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->roll = roll; - packet->pitch = pitch; - packet->yaw = yaw; - packet->id = id; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)packet, MAVLINK_MSG_ID_MARKER_LEN, MAVLINK_MSG_ID_MARKER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MARKER, (const char *)packet, MAVLINK_MSG_ID_MARKER_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE MARKER UNPACKING - - -/** - * @brief Get field id from marker message - * - * @return ID - */ -static inline uint16_t mavlink_msg_marker_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field x from marker message - * - * @return x position - */ -static inline float mavlink_msg_marker_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field y from marker message - * - * @return y position - */ -static inline float mavlink_msg_marker_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field z from marker message - * - * @return z position - */ -static inline float mavlink_msg_marker_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field roll from marker message - * - * @return roll orientation - */ -static inline float mavlink_msg_marker_get_roll(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field pitch from marker message - * - * @return pitch orientation - */ -static inline float mavlink_msg_marker_get_pitch(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field yaw from marker message - * - * @return yaw orientation - */ -static inline float mavlink_msg_marker_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Decode a marker message into a struct - * - * @param msg The message to decode - * @param marker C-struct to decode the message contents into - */ -static inline void mavlink_msg_marker_decode(const mavlink_message_t* msg, mavlink_marker_t* marker) -{ -#if MAVLINK_NEED_BYTE_SWAP - marker->x = mavlink_msg_marker_get_x(msg); - marker->y = mavlink_msg_marker_get_y(msg); - marker->z = mavlink_msg_marker_get_z(msg); - marker->roll = mavlink_msg_marker_get_roll(msg); - marker->pitch = mavlink_msg_marker_get_pitch(msg); - marker->yaw = mavlink_msg_marker_get_yaw(msg); - marker->id = mavlink_msg_marker_get_id(msg); -#else - memcpy(marker, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MARKER_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h deleted file mode 100644 index bde400da9..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_pattern_detected.h +++ /dev/null @@ -1,273 +0,0 @@ -// MESSAGE PATTERN_DETECTED PACKING - -#define MAVLINK_MSG_ID_PATTERN_DETECTED 190 - -typedef struct __mavlink_pattern_detected_t -{ - float confidence; ///< Confidence of detection - uint8_t type; ///< 0: Pattern, 1: Letter - char file[100]; ///< Pattern file name - uint8_t detected; ///< Accepted as true detection, 0 no, 1 yes -} mavlink_pattern_detected_t; - -#define MAVLINK_MSG_ID_PATTERN_DETECTED_LEN 106 -#define MAVLINK_MSG_ID_190_LEN 106 - -#define MAVLINK_MSG_ID_PATTERN_DETECTED_CRC 90 -#define MAVLINK_MSG_ID_190_CRC 90 - -#define MAVLINK_MSG_PATTERN_DETECTED_FIELD_FILE_LEN 100 - -#define MAVLINK_MESSAGE_INFO_PATTERN_DETECTED { \ - "PATTERN_DETECTED", \ - 4, \ - { { "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pattern_detected_t, confidence) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_pattern_detected_t, type) }, \ - { "file", NULL, MAVLINK_TYPE_CHAR, 100, 5, offsetof(mavlink_pattern_detected_t, file) }, \ - { "detected", NULL, MAVLINK_TYPE_UINT8_T, 0, 105, offsetof(mavlink_pattern_detected_t, detected) }, \ - } \ -} - - -/** - * @brief Pack a pattern_detected message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type 0: Pattern, 1: Letter - * @param confidence Confidence of detection - * @param file Pattern file name - * @param detected Accepted as true detection, 0 no, 1 yes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_pattern_detected_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, float confidence, const char *file, uint8_t detected) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PATTERN_DETECTED_LEN]; - _mav_put_float(buf, 0, confidence); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 105, detected); - _mav_put_char_array(buf, 5, file, 100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#else - mavlink_pattern_detected_t packet; - packet.confidence = confidence; - packet.type = type; - packet.detected = detected; - mav_array_memcpy(packet.file, file, sizeof(char)*100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#endif -} - -/** - * @brief Pack a pattern_detected message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type 0: Pattern, 1: Letter - * @param confidence Confidence of detection - * @param file Pattern file name - * @param detected Accepted as true detection, 0 no, 1 yes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_pattern_detected_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,float confidence,const char *file,uint8_t detected) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PATTERN_DETECTED_LEN]; - _mav_put_float(buf, 0, confidence); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 105, detected); - _mav_put_char_array(buf, 5, file, 100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#else - mavlink_pattern_detected_t packet; - packet.confidence = confidence; - packet.type = type; - packet.detected = detected; - mav_array_memcpy(packet.file, file, sizeof(char)*100); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PATTERN_DETECTED; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#endif -} - -/** - * @brief Encode a pattern_detected struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param pattern_detected C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_pattern_detected_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected) -{ - return mavlink_msg_pattern_detected_pack(system_id, component_id, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected); -} - -/** - * @brief Encode a pattern_detected struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param pattern_detected C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_pattern_detected_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pattern_detected_t* pattern_detected) -{ - return mavlink_msg_pattern_detected_pack_chan(system_id, component_id, chan, msg, pattern_detected->type, pattern_detected->confidence, pattern_detected->file, pattern_detected->detected); -} - -/** - * @brief Send a pattern_detected message - * @param chan MAVLink channel to send the message - * - * @param type 0: Pattern, 1: Letter - * @param confidence Confidence of detection - * @param file Pattern file name - * @param detected Accepted as true detection, 0 no, 1 yes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_pattern_detected_send(mavlink_channel_t chan, uint8_t type, float confidence, const char *file, uint8_t detected) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PATTERN_DETECTED_LEN]; - _mav_put_float(buf, 0, confidence); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 105, detected); - _mav_put_char_array(buf, 5, file, 100); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#endif -#else - mavlink_pattern_detected_t packet; - packet.confidence = confidence; - packet.type = type; - packet.detected = detected; - mav_array_memcpy(packet.file, file, sizeof(char)*100); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)&packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)&packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_PATTERN_DETECTED_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_pattern_detected_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, float confidence, const char *file, uint8_t detected) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, confidence); - _mav_put_uint8_t(buf, 4, type); - _mav_put_uint8_t(buf, 105, detected); - _mav_put_char_array(buf, 5, file, 100); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, buf, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#endif -#else - mavlink_pattern_detected_t *packet = (mavlink_pattern_detected_t *)msgbuf; - packet->confidence = confidence; - packet->type = type; - packet->detected = detected; - mav_array_memcpy(packet->file, file, sizeof(char)*100); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN, MAVLINK_MSG_ID_PATTERN_DETECTED_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PATTERN_DETECTED, (const char *)packet, MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE PATTERN_DETECTED UNPACKING - - -/** - * @brief Get field type from pattern_detected message - * - * @return 0: Pattern, 1: Letter - */ -static inline uint8_t mavlink_msg_pattern_detected_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field confidence from pattern_detected message - * - * @return Confidence of detection - */ -static inline float mavlink_msg_pattern_detected_get_confidence(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field file from pattern_detected message - * - * @return Pattern file name - */ -static inline uint16_t mavlink_msg_pattern_detected_get_file(const mavlink_message_t* msg, char *file) -{ - return _MAV_RETURN_char_array(msg, file, 100, 5); -} - -/** - * @brief Get field detected from pattern_detected message - * - * @return Accepted as true detection, 0 no, 1 yes - */ -static inline uint8_t mavlink_msg_pattern_detected_get_detected(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 105); -} - -/** - * @brief Decode a pattern_detected message into a struct - * - * @param msg The message to decode - * @param pattern_detected C-struct to decode the message contents into - */ -static inline void mavlink_msg_pattern_detected_decode(const mavlink_message_t* msg, mavlink_pattern_detected_t* pattern_detected) -{ -#if MAVLINK_NEED_BYTE_SWAP - pattern_detected->confidence = mavlink_msg_pattern_detected_get_confidence(msg); - pattern_detected->type = mavlink_msg_pattern_detected_get_type(msg); - mavlink_msg_pattern_detected_get_file(msg, pattern_detected->file); - pattern_detected->detected = mavlink_msg_pattern_detected_get_detected(msg); -#else - memcpy(pattern_detected, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PATTERN_DETECTED_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h deleted file mode 100644 index 86e934519..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest.h +++ /dev/null @@ -1,369 +0,0 @@ -// MESSAGE POINT_OF_INTEREST PACKING - -#define MAVLINK_MSG_ID_POINT_OF_INTEREST 191 - -typedef struct __mavlink_point_of_interest_t -{ - float x; ///< X Position - float y; ///< Y Position - float z; ///< Z Position - uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds - uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - uint8_t coordinate_system; ///< 0: global, 1:local - char name[26]; ///< POI name -} mavlink_point_of_interest_t; - -#define MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN 43 -#define MAVLINK_MSG_ID_191_LEN 43 - -#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC 95 -#define MAVLINK_MSG_ID_191_CRC 95 - -#define MAVLINK_MSG_POINT_OF_INTEREST_FIELD_NAME_LEN 26 - -#define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST { \ - "POINT_OF_INTEREST", \ - 8, \ - { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_point_of_interest_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_point_of_interest_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_point_of_interest_t, z) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_point_of_interest_t, timeout) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_point_of_interest_t, type) }, \ - { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_point_of_interest_t, color) }, \ - { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_point_of_interest_t, coordinate_system) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 26, 17, offsetof(mavlink_point_of_interest_t, name) }, \ - } \ -} - - -/** - * @brief Pack a point_of_interest message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - * @param coordinate_system 0: global, 1:local - * @param timeout 0: no timeout, >1: timeout in seconds - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param name POI name - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_point_of_interest_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_uint16_t(buf, 12, timeout); - _mav_put_uint8_t(buf, 14, type); - _mav_put_uint8_t(buf, 15, color); - _mav_put_uint8_t(buf, 16, coordinate_system); - _mav_put_char_array(buf, 17, name, 26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#else - mavlink_point_of_interest_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.timeout = timeout; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#endif -} - -/** - * @brief Pack a point_of_interest message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - * @param coordinate_system 0: global, 1:local - * @param timeout 0: no timeout, >1: timeout in seconds - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param name POI name - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_point_of_interest_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t color,uint8_t coordinate_system,uint16_t timeout,float x,float y,float z,const char *name) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_uint16_t(buf, 12, timeout); - _mav_put_uint8_t(buf, 14, type); - _mav_put_uint8_t(buf, 15, color); - _mav_put_uint8_t(buf, 16, coordinate_system); - _mav_put_char_array(buf, 17, name, 26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#else - mavlink_point_of_interest_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.timeout = timeout; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#endif -} - -/** - * @brief Encode a point_of_interest struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param point_of_interest C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_point_of_interest_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest) -{ - return mavlink_msg_point_of_interest_pack(system_id, component_id, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name); -} - -/** - * @brief Encode a point_of_interest struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param point_of_interest C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_point_of_interest_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_point_of_interest_t* point_of_interest) -{ - return mavlink_msg_point_of_interest_pack_chan(system_id, component_id, chan, msg, point_of_interest->type, point_of_interest->color, point_of_interest->coordinate_system, point_of_interest->timeout, point_of_interest->x, point_of_interest->y, point_of_interest->z, point_of_interest->name); -} - -/** - * @brief Send a point_of_interest message - * @param chan MAVLink channel to send the message - * - * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - * @param coordinate_system 0: global, 1:local - * @param timeout 0: no timeout, >1: timeout in seconds - * @param x X Position - * @param y Y Position - * @param z Z Position - * @param name POI name - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_point_of_interest_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_uint16_t(buf, 12, timeout); - _mav_put_uint8_t(buf, 14, type); - _mav_put_uint8_t(buf, 15, color); - _mav_put_uint8_t(buf, 16, coordinate_system); - _mav_put_char_array(buf, 17, name, 26); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#endif -#else - mavlink_point_of_interest_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.timeout = timeout; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - mav_array_memcpy(packet.name, name, sizeof(char)*26); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)&packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)&packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_point_of_interest_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float x, float y, float z, const char *name) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_uint16_t(buf, 12, timeout); - _mav_put_uint8_t(buf, 14, type); - _mav_put_uint8_t(buf, 15, color); - _mav_put_uint8_t(buf, 16, coordinate_system); - _mav_put_char_array(buf, 17, name, 26); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#endif -#else - mavlink_point_of_interest_t *packet = (mavlink_point_of_interest_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->timeout = timeout; - packet->type = type; - packet->color = color; - packet->coordinate_system = coordinate_system; - mav_array_memcpy(packet->name, name, sizeof(char)*26); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST, (const char *)packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE POINT_OF_INTEREST UNPACKING - - -/** - * @brief Get field type from point_of_interest message - * - * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - */ -static inline uint8_t mavlink_msg_point_of_interest_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 14); -} - -/** - * @brief Get field color from point_of_interest message - * - * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - */ -static inline uint8_t mavlink_msg_point_of_interest_get_color(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 15); -} - -/** - * @brief Get field coordinate_system from point_of_interest message - * - * @return 0: global, 1:local - */ -static inline uint8_t mavlink_msg_point_of_interest_get_coordinate_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field timeout from point_of_interest message - * - * @return 0: no timeout, >1: timeout in seconds - */ -static inline uint16_t mavlink_msg_point_of_interest_get_timeout(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field x from point_of_interest message - * - * @return X Position - */ -static inline float mavlink_msg_point_of_interest_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field y from point_of_interest message - * - * @return Y Position - */ -static inline float mavlink_msg_point_of_interest_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field z from point_of_interest message - * - * @return Z Position - */ -static inline float mavlink_msg_point_of_interest_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field name from point_of_interest message - * - * @return POI name - */ -static inline uint16_t mavlink_msg_point_of_interest_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 26, 17); -} - -/** - * @brief Decode a point_of_interest message into a struct - * - * @param msg The message to decode - * @param point_of_interest C-struct to decode the message contents into - */ -static inline void mavlink_msg_point_of_interest_decode(const mavlink_message_t* msg, mavlink_point_of_interest_t* point_of_interest) -{ -#if MAVLINK_NEED_BYTE_SWAP - point_of_interest->x = mavlink_msg_point_of_interest_get_x(msg); - point_of_interest->y = mavlink_msg_point_of_interest_get_y(msg); - point_of_interest->z = mavlink_msg_point_of_interest_get_z(msg); - point_of_interest->timeout = mavlink_msg_point_of_interest_get_timeout(msg); - point_of_interest->type = mavlink_msg_point_of_interest_get_type(msg); - point_of_interest->color = mavlink_msg_point_of_interest_get_color(msg); - point_of_interest->coordinate_system = mavlink_msg_point_of_interest_get_coordinate_system(msg); - mavlink_msg_point_of_interest_get_name(msg, point_of_interest->name); -#else - memcpy(point_of_interest, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POINT_OF_INTEREST_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h deleted file mode 100644 index e5c04a851..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_point_of_interest_connection.h +++ /dev/null @@ -1,441 +0,0 @@ -// MESSAGE POINT_OF_INTEREST_CONNECTION PACKING - -#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION 192 - -typedef struct __mavlink_point_of_interest_connection_t -{ - float xp1; ///< X1 Position - float yp1; ///< Y1 Position - float zp1; ///< Z1 Position - float xp2; ///< X2 Position - float yp2; ///< Y2 Position - float zp2; ///< Z2 Position - uint16_t timeout; ///< 0: no timeout, >1: timeout in seconds - uint8_t type; ///< 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - uint8_t color; ///< 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - uint8_t coordinate_system; ///< 0: global, 1:local - char name[26]; ///< POI connection name -} mavlink_point_of_interest_connection_t; - -#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN 55 -#define MAVLINK_MSG_ID_192_LEN 55 - -#define MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC 36 -#define MAVLINK_MSG_ID_192_CRC 36 - -#define MAVLINK_MSG_POINT_OF_INTEREST_CONNECTION_FIELD_NAME_LEN 26 - -#define MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION { \ - "POINT_OF_INTEREST_CONNECTION", \ - 11, \ - { { "xp1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_point_of_interest_connection_t, xp1) }, \ - { "yp1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_point_of_interest_connection_t, yp1) }, \ - { "zp1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_point_of_interest_connection_t, zp1) }, \ - { "xp2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_point_of_interest_connection_t, xp2) }, \ - { "yp2", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_point_of_interest_connection_t, yp2) }, \ - { "zp2", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_point_of_interest_connection_t, zp2) }, \ - { "timeout", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_point_of_interest_connection_t, timeout) }, \ - { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_point_of_interest_connection_t, type) }, \ - { "color", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_point_of_interest_connection_t, color) }, \ - { "coordinate_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_point_of_interest_connection_t, coordinate_system) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 26, 29, offsetof(mavlink_point_of_interest_connection_t, name) }, \ - } \ -} - - -/** - * @brief Pack a point_of_interest_connection message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - * @param coordinate_system 0: global, 1:local - * @param timeout 0: no timeout, >1: timeout in seconds - * @param xp1 X1 Position - * @param yp1 Y1 Position - * @param zp1 Z1 Position - * @param xp2 X2 Position - * @param yp2 Y2 Position - * @param zp2 Z2 Position - * @param name POI connection name - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_point_of_interest_connection_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN]; - _mav_put_float(buf, 0, xp1); - _mav_put_float(buf, 4, yp1); - _mav_put_float(buf, 8, zp1); - _mav_put_float(buf, 12, xp2); - _mav_put_float(buf, 16, yp2); - _mav_put_float(buf, 20, zp2); - _mav_put_uint16_t(buf, 24, timeout); - _mav_put_uint8_t(buf, 26, type); - _mav_put_uint8_t(buf, 27, color); - _mav_put_uint8_t(buf, 28, coordinate_system); - _mav_put_char_array(buf, 29, name, 26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#else - mavlink_point_of_interest_connection_t packet; - packet.xp1 = xp1; - packet.yp1 = yp1; - packet.zp1 = zp1; - packet.xp2 = xp2; - packet.yp2 = yp2; - packet.zp2 = zp2; - packet.timeout = timeout; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#endif -} - -/** - * @brief Pack a point_of_interest_connection message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - * @param coordinate_system 0: global, 1:local - * @param timeout 0: no timeout, >1: timeout in seconds - * @param xp1 X1 Position - * @param yp1 Y1 Position - * @param zp1 Z1 Position - * @param xp2 X2 Position - * @param yp2 Y2 Position - * @param zp2 Z2 Position - * @param name POI connection name - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_point_of_interest_connection_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t type,uint8_t color,uint8_t coordinate_system,uint16_t timeout,float xp1,float yp1,float zp1,float xp2,float yp2,float zp2,const char *name) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN]; - _mav_put_float(buf, 0, xp1); - _mav_put_float(buf, 4, yp1); - _mav_put_float(buf, 8, zp1); - _mav_put_float(buf, 12, xp2); - _mav_put_float(buf, 16, yp2); - _mav_put_float(buf, 20, zp2); - _mav_put_uint16_t(buf, 24, timeout); - _mav_put_uint8_t(buf, 26, type); - _mav_put_uint8_t(buf, 27, color); - _mav_put_uint8_t(buf, 28, coordinate_system); - _mav_put_char_array(buf, 29, name, 26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#else - mavlink_point_of_interest_connection_t packet; - packet.xp1 = xp1; - packet.yp1 = yp1; - packet.zp1 = zp1; - packet.xp2 = xp2; - packet.yp2 = yp2; - packet.zp2 = zp2; - packet.timeout = timeout; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - mav_array_memcpy(packet.name, name, sizeof(char)*26); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#endif -} - -/** - * @brief Encode a point_of_interest_connection struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param point_of_interest_connection C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_point_of_interest_connection_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection) -{ - return mavlink_msg_point_of_interest_connection_pack(system_id, component_id, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name); -} - -/** - * @brief Encode a point_of_interest_connection struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param point_of_interest_connection C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_point_of_interest_connection_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_point_of_interest_connection_t* point_of_interest_connection) -{ - return mavlink_msg_point_of_interest_connection_pack_chan(system_id, component_id, chan, msg, point_of_interest_connection->type, point_of_interest_connection->color, point_of_interest_connection->coordinate_system, point_of_interest_connection->timeout, point_of_interest_connection->xp1, point_of_interest_connection->yp1, point_of_interest_connection->zp1, point_of_interest_connection->xp2, point_of_interest_connection->yp2, point_of_interest_connection->zp2, point_of_interest_connection->name); -} - -/** - * @brief Send a point_of_interest_connection message - * @param chan MAVLink channel to send the message - * - * @param type 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - * @param color 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - * @param coordinate_system 0: global, 1:local - * @param timeout 0: no timeout, >1: timeout in seconds - * @param xp1 X1 Position - * @param yp1 Y1 Position - * @param zp1 Z1 Position - * @param xp2 X2 Position - * @param yp2 Y2 Position - * @param zp2 Z2 Position - * @param name POI connection name - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_point_of_interest_connection_send(mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN]; - _mav_put_float(buf, 0, xp1); - _mav_put_float(buf, 4, yp1); - _mav_put_float(buf, 8, zp1); - _mav_put_float(buf, 12, xp2); - _mav_put_float(buf, 16, yp2); - _mav_put_float(buf, 20, zp2); - _mav_put_uint16_t(buf, 24, timeout); - _mav_put_uint8_t(buf, 26, type); - _mav_put_uint8_t(buf, 27, color); - _mav_put_uint8_t(buf, 28, coordinate_system); - _mav_put_char_array(buf, 29, name, 26); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#endif -#else - mavlink_point_of_interest_connection_t packet; - packet.xp1 = xp1; - packet.yp1 = yp1; - packet.zp1 = zp1; - packet.xp2 = xp2; - packet.yp2 = yp2; - packet.zp2 = zp2; - packet.timeout = timeout; - packet.type = type; - packet.color = color; - packet.coordinate_system = coordinate_system; - mav_array_memcpy(packet.name, name, sizeof(char)*26); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)&packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)&packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_point_of_interest_connection_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t color, uint8_t coordinate_system, uint16_t timeout, float xp1, float yp1, float zp1, float xp2, float yp2, float zp2, const char *name) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, xp1); - _mav_put_float(buf, 4, yp1); - _mav_put_float(buf, 8, zp1); - _mav_put_float(buf, 12, xp2); - _mav_put_float(buf, 16, yp2); - _mav_put_float(buf, 20, zp2); - _mav_put_uint16_t(buf, 24, timeout); - _mav_put_uint8_t(buf, 26, type); - _mav_put_uint8_t(buf, 27, color); - _mav_put_uint8_t(buf, 28, coordinate_system); - _mav_put_char_array(buf, 29, name, 26); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, buf, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#endif -#else - mavlink_point_of_interest_connection_t *packet = (mavlink_point_of_interest_connection_t *)msgbuf; - packet->xp1 = xp1; - packet->yp1 = yp1; - packet->zp1 = zp1; - packet->xp2 = xp2; - packet->yp2 = yp2; - packet->zp2 = zp2; - packet->timeout = timeout; - packet->type = type; - packet->color = color; - packet->coordinate_system = coordinate_system; - mav_array_memcpy(packet->name, name, sizeof(char)*26); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION, (const char *)packet, MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE POINT_OF_INTEREST_CONNECTION UNPACKING - - -/** - * @brief Get field type from point_of_interest_connection message - * - * @return 0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug - */ -static inline uint8_t mavlink_msg_point_of_interest_connection_get_type(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 26); -} - -/** - * @brief Get field color from point_of_interest_connection message - * - * @return 0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta - */ -static inline uint8_t mavlink_msg_point_of_interest_connection_get_color(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 27); -} - -/** - * @brief Get field coordinate_system from point_of_interest_connection message - * - * @return 0: global, 1:local - */ -static inline uint8_t mavlink_msg_point_of_interest_connection_get_coordinate_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 28); -} - -/** - * @brief Get field timeout from point_of_interest_connection message - * - * @return 0: no timeout, >1: timeout in seconds - */ -static inline uint16_t mavlink_msg_point_of_interest_connection_get_timeout(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 24); -} - -/** - * @brief Get field xp1 from point_of_interest_connection message - * - * @return X1 Position - */ -static inline float mavlink_msg_point_of_interest_connection_get_xp1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field yp1 from point_of_interest_connection message - * - * @return Y1 Position - */ -static inline float mavlink_msg_point_of_interest_connection_get_yp1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field zp1 from point_of_interest_connection message - * - * @return Z1 Position - */ -static inline float mavlink_msg_point_of_interest_connection_get_zp1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field xp2 from point_of_interest_connection message - * - * @return X2 Position - */ -static inline float mavlink_msg_point_of_interest_connection_get_xp2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Get field yp2 from point_of_interest_connection message - * - * @return Y2 Position - */ -static inline float mavlink_msg_point_of_interest_connection_get_yp2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 16); -} - -/** - * @brief Get field zp2 from point_of_interest_connection message - * - * @return Z2 Position - */ -static inline float mavlink_msg_point_of_interest_connection_get_zp2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 20); -} - -/** - * @brief Get field name from point_of_interest_connection message - * - * @return POI connection name - */ -static inline uint16_t mavlink_msg_point_of_interest_connection_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 26, 29); -} - -/** - * @brief Decode a point_of_interest_connection message into a struct - * - * @param msg The message to decode - * @param point_of_interest_connection C-struct to decode the message contents into - */ -static inline void mavlink_msg_point_of_interest_connection_decode(const mavlink_message_t* msg, mavlink_point_of_interest_connection_t* point_of_interest_connection) -{ -#if MAVLINK_NEED_BYTE_SWAP - point_of_interest_connection->xp1 = mavlink_msg_point_of_interest_connection_get_xp1(msg); - point_of_interest_connection->yp1 = mavlink_msg_point_of_interest_connection_get_yp1(msg); - point_of_interest_connection->zp1 = mavlink_msg_point_of_interest_connection_get_zp1(msg); - point_of_interest_connection->xp2 = mavlink_msg_point_of_interest_connection_get_xp2(msg); - point_of_interest_connection->yp2 = mavlink_msg_point_of_interest_connection_get_yp2(msg); - point_of_interest_connection->zp2 = mavlink_msg_point_of_interest_connection_get_zp2(msg); - point_of_interest_connection->timeout = mavlink_msg_point_of_interest_connection_get_timeout(msg); - point_of_interest_connection->type = mavlink_msg_point_of_interest_connection_get_type(msg); - point_of_interest_connection->color = mavlink_msg_point_of_interest_connection_get_color(msg); - point_of_interest_connection->coordinate_system = mavlink_msg_point_of_interest_connection_get_coordinate_system(msg); - mavlink_msg_point_of_interest_connection_get_name(msg, point_of_interest_connection->name); -#else - memcpy(point_of_interest_connection, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POINT_OF_INTEREST_CONNECTION_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h deleted file mode 100644 index 480004cef..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_position_control_setpoint.h +++ /dev/null @@ -1,305 +0,0 @@ -// MESSAGE POSITION_CONTROL_SETPOINT PACKING - -#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT 170 - -typedef struct __mavlink_position_control_setpoint_t -{ - float x; ///< x position - float y; ///< y position - float z; ///< z position - float yaw; ///< yaw orientation in radians, 0 = NORTH - uint16_t id; ///< ID of waypoint, 0 for plain position -} mavlink_position_control_setpoint_t; - -#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN 18 -#define MAVLINK_MSG_ID_170_LEN 18 - -#define MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC 28 -#define MAVLINK_MSG_ID_170_CRC 28 - - - -#define MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT { \ - "POSITION_CONTROL_SETPOINT", \ - 5, \ - { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_position_control_setpoint_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_control_setpoint_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_control_setpoint_t, z) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_control_setpoint_t, yaw) }, \ - { "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_position_control_setpoint_t, id) }, \ - } \ -} - - -/** - * @brief Pack a position_control_setpoint message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param id ID of waypoint, 0 for plain position - * @param x x position - * @param y y position - * @param z z position - * @param yaw yaw orientation in radians, 0 = NORTH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_control_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t id, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint16_t(buf, 16, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#else - mavlink_position_control_setpoint_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#endif -} - -/** - * @brief Pack a position_control_setpoint message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param id ID of waypoint, 0 for plain position - * @param x x position - * @param y y position - * @param z z position - * @param yaw yaw orientation in radians, 0 = NORTH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_position_control_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t id,float x,float y,float z,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint16_t(buf, 16, id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#else - mavlink_position_control_setpoint_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.id = id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#endif -} - -/** - * @brief Encode a position_control_setpoint struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param position_control_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_control_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint) -{ - return mavlink_msg_position_control_setpoint_pack(system_id, component_id, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw); -} - -/** - * @brief Encode a position_control_setpoint struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param position_control_setpoint C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_position_control_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_control_setpoint_t* position_control_setpoint) -{ - return mavlink_msg_position_control_setpoint_pack_chan(system_id, component_id, chan, msg, position_control_setpoint->id, position_control_setpoint->x, position_control_setpoint->y, position_control_setpoint->z, position_control_setpoint->yaw); -} - -/** - * @brief Send a position_control_setpoint message - * @param chan MAVLink channel to send the message - * - * @param id ID of waypoint, 0 for plain position - * @param x x position - * @param y y position - * @param z z position - * @param yaw yaw orientation in radians, 0 = NORTH - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_position_control_setpoint_send(mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint16_t(buf, 16, id); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#endif -#else - mavlink_position_control_setpoint_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.id = id; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_position_control_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint16_t(buf, 16, id); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, buf, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#endif -#else - mavlink_position_control_setpoint_t *packet = (mavlink_position_control_setpoint_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->yaw = yaw; - packet->id = id; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE POSITION_CONTROL_SETPOINT UNPACKING - - -/** - * @brief Get field id from position_control_setpoint message - * - * @return ID of waypoint, 0 for plain position - */ -static inline uint16_t mavlink_msg_position_control_setpoint_get_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 16); -} - -/** - * @brief Get field x from position_control_setpoint message - * - * @return x position - */ -static inline float mavlink_msg_position_control_setpoint_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field y from position_control_setpoint message - * - * @return y position - */ -static inline float mavlink_msg_position_control_setpoint_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field z from position_control_setpoint message - * - * @return z position - */ -static inline float mavlink_msg_position_control_setpoint_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from position_control_setpoint message - * - * @return yaw orientation in radians, 0 = NORTH - */ -static inline float mavlink_msg_position_control_setpoint_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a position_control_setpoint message into a struct - * - * @param msg The message to decode - * @param position_control_setpoint C-struct to decode the message contents into - */ -static inline void mavlink_msg_position_control_setpoint_decode(const mavlink_message_t* msg, mavlink_position_control_setpoint_t* position_control_setpoint) -{ -#if MAVLINK_NEED_BYTE_SWAP - position_control_setpoint->x = mavlink_msg_position_control_setpoint_get_x(msg); - position_control_setpoint->y = mavlink_msg_position_control_setpoint_get_y(msg); - position_control_setpoint->z = mavlink_msg_position_control_setpoint_get_z(msg); - position_control_setpoint->yaw = mavlink_msg_position_control_setpoint_get_yaw(msg); - position_control_setpoint->id = mavlink_msg_position_control_setpoint_get_id(msg); -#else - memcpy(position_control_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_CONTROL_SETPOINT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h deleted file mode 100644 index 41a512648..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_raw_aux.h +++ /dev/null @@ -1,353 +0,0 @@ -// MESSAGE RAW_AUX PACKING - -#define MAVLINK_MSG_ID_RAW_AUX 172 - -typedef struct __mavlink_raw_aux_t -{ - int32_t baro; ///< Barometric pressure (hecto Pascal) - uint16_t adc1; ///< ADC1 (J405 ADC3, LPC2148 AD0.6) - uint16_t adc2; ///< ADC2 (J405 ADC5, LPC2148 AD0.2) - uint16_t adc3; ///< ADC3 (J405 ADC6, LPC2148 AD0.1) - uint16_t adc4; ///< ADC4 (J405 ADC7, LPC2148 AD1.3) - uint16_t vbat; ///< Battery voltage - int16_t temp; ///< Temperature (degrees celcius) -} mavlink_raw_aux_t; - -#define MAVLINK_MSG_ID_RAW_AUX_LEN 16 -#define MAVLINK_MSG_ID_172_LEN 16 - -#define MAVLINK_MSG_ID_RAW_AUX_CRC 182 -#define MAVLINK_MSG_ID_172_CRC 182 - - - -#define MAVLINK_MESSAGE_INFO_RAW_AUX { \ - "RAW_AUX", \ - 7, \ - { { "baro", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_raw_aux_t, baro) }, \ - { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_raw_aux_t, adc1) }, \ - { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_raw_aux_t, adc2) }, \ - { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_raw_aux_t, adc3) }, \ - { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_raw_aux_t, adc4) }, \ - { "vbat", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_raw_aux_t, vbat) }, \ - { "temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_aux_t, temp) }, \ - } \ -} - - -/** - * @brief Pack a raw_aux message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) - * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) - * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) - * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) - * @param vbat Battery voltage - * @param temp Temperature (degrees celcius) - * @param baro Barometric pressure (hecto Pascal) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_aux_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_AUX_LEN]; - _mav_put_int32_t(buf, 0, baro); - _mav_put_uint16_t(buf, 4, adc1); - _mav_put_uint16_t(buf, 6, adc2); - _mav_put_uint16_t(buf, 8, adc3); - _mav_put_uint16_t(buf, 10, adc4); - _mav_put_uint16_t(buf, 12, vbat); - _mav_put_int16_t(buf, 14, temp); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_AUX_LEN); -#else - mavlink_raw_aux_t packet; - packet.baro = baro; - packet.adc1 = adc1; - packet.adc2 = adc2; - packet.adc3 = adc3; - packet.adc4 = adc4; - packet.vbat = vbat; - packet.temp = temp; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_AUX_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_AUX; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_AUX_LEN); -#endif -} - -/** - * @brief Pack a raw_aux message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) - * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) - * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) - * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) - * @param vbat Battery voltage - * @param temp Temperature (degrees celcius) - * @param baro Barometric pressure (hecto Pascal) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_raw_aux_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t vbat,int16_t temp,int32_t baro) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_AUX_LEN]; - _mav_put_int32_t(buf, 0, baro); - _mav_put_uint16_t(buf, 4, adc1); - _mav_put_uint16_t(buf, 6, adc2); - _mav_put_uint16_t(buf, 8, adc3); - _mav_put_uint16_t(buf, 10, adc4); - _mav_put_uint16_t(buf, 12, vbat); - _mav_put_int16_t(buf, 14, temp); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RAW_AUX_LEN); -#else - mavlink_raw_aux_t packet; - packet.baro = baro; - packet.adc1 = adc1; - packet.adc2 = adc2; - packet.adc3 = adc3; - packet.adc4 = adc4; - packet.vbat = vbat; - packet.temp = temp; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RAW_AUX_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_RAW_AUX; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_AUX_LEN); -#endif -} - -/** - * @brief Encode a raw_aux struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param raw_aux C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_aux_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux) -{ - return mavlink_msg_raw_aux_pack(system_id, component_id, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro); -} - -/** - * @brief Encode a raw_aux struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param raw_aux C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_raw_aux_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_aux_t* raw_aux) -{ - return mavlink_msg_raw_aux_pack_chan(system_id, component_id, chan, msg, raw_aux->adc1, raw_aux->adc2, raw_aux->adc3, raw_aux->adc4, raw_aux->vbat, raw_aux->temp, raw_aux->baro); -} - -/** - * @brief Send a raw_aux message - * @param chan MAVLink channel to send the message - * - * @param adc1 ADC1 (J405 ADC3, LPC2148 AD0.6) - * @param adc2 ADC2 (J405 ADC5, LPC2148 AD0.2) - * @param adc3 ADC3 (J405 ADC6, LPC2148 AD0.1) - * @param adc4 ADC4 (J405 ADC7, LPC2148 AD1.3) - * @param vbat Battery voltage - * @param temp Temperature (degrees celcius) - * @param baro Barometric pressure (hecto Pascal) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_raw_aux_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_RAW_AUX_LEN]; - _mav_put_int32_t(buf, 0, baro); - _mav_put_uint16_t(buf, 4, adc1); - _mav_put_uint16_t(buf, 6, adc2); - _mav_put_uint16_t(buf, 8, adc3); - _mav_put_uint16_t(buf, 10, adc4); - _mav_put_uint16_t(buf, 12, vbat); - _mav_put_int16_t(buf, 14, temp); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN); -#endif -#else - mavlink_raw_aux_t packet; - packet.baro = baro; - packet.adc1 = adc1; - packet.adc2 = adc2; - packet.adc3 = adc3; - packet.adc4 = adc4; - packet.vbat = vbat; - packet.temp = temp; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)&packet, MAVLINK_MSG_ID_RAW_AUX_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_RAW_AUX_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_raw_aux_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t vbat, int16_t temp, int32_t baro) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, baro); - _mav_put_uint16_t(buf, 4, adc1); - _mav_put_uint16_t(buf, 6, adc2); - _mav_put_uint16_t(buf, 8, adc3); - _mav_put_uint16_t(buf, 10, adc4); - _mav_put_uint16_t(buf, 12, vbat); - _mav_put_int16_t(buf, 14, temp); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, buf, MAVLINK_MSG_ID_RAW_AUX_LEN); -#endif -#else - mavlink_raw_aux_t *packet = (mavlink_raw_aux_t *)msgbuf; - packet->baro = baro; - packet->adc1 = adc1; - packet->adc2 = adc2; - packet->adc3 = adc3; - packet->adc4 = adc4; - packet->vbat = vbat; - packet->temp = temp; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)packet, MAVLINK_MSG_ID_RAW_AUX_LEN, MAVLINK_MSG_ID_RAW_AUX_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_AUX, (const char *)packet, MAVLINK_MSG_ID_RAW_AUX_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE RAW_AUX UNPACKING - - -/** - * @brief Get field adc1 from raw_aux message - * - * @return ADC1 (J405 ADC3, LPC2148 AD0.6) - */ -static inline uint16_t mavlink_msg_raw_aux_get_adc1(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field adc2 from raw_aux message - * - * @return ADC2 (J405 ADC5, LPC2148 AD0.2) - */ -static inline uint16_t mavlink_msg_raw_aux_get_adc2(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field adc3 from raw_aux message - * - * @return ADC3 (J405 ADC6, LPC2148 AD0.1) - */ -static inline uint16_t mavlink_msg_raw_aux_get_adc3(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Get field adc4 from raw_aux message - * - * @return ADC4 (J405 ADC7, LPC2148 AD1.3) - */ -static inline uint16_t mavlink_msg_raw_aux_get_adc4(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 10); -} - -/** - * @brief Get field vbat from raw_aux message - * - * @return Battery voltage - */ -static inline uint16_t mavlink_msg_raw_aux_get_vbat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field temp from raw_aux message - * - * @return Temperature (degrees celcius) - */ -static inline int16_t mavlink_msg_raw_aux_get_temp(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 14); -} - -/** - * @brief Get field baro from raw_aux message - * - * @return Barometric pressure (hecto Pascal) - */ -static inline int32_t mavlink_msg_raw_aux_get_baro(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Decode a raw_aux message into a struct - * - * @param msg The message to decode - * @param raw_aux C-struct to decode the message contents into - */ -static inline void mavlink_msg_raw_aux_decode(const mavlink_message_t* msg, mavlink_raw_aux_t* raw_aux) -{ -#if MAVLINK_NEED_BYTE_SWAP - raw_aux->baro = mavlink_msg_raw_aux_get_baro(msg); - raw_aux->adc1 = mavlink_msg_raw_aux_get_adc1(msg); - raw_aux->adc2 = mavlink_msg_raw_aux_get_adc2(msg); - raw_aux->adc3 = mavlink_msg_raw_aux_get_adc3(msg); - raw_aux->adc4 = mavlink_msg_raw_aux_get_adc4(msg); - raw_aux->vbat = mavlink_msg_raw_aux_get_vbat(msg); - raw_aux->temp = mavlink_msg_raw_aux_get_temp(msg); -#else - memcpy(raw_aux, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RAW_AUX_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h deleted file mode 100644 index 8fe14dd54..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_cam_shutter.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE SET_CAM_SHUTTER PACKING - -#define MAVLINK_MSG_ID_SET_CAM_SHUTTER 151 - -typedef struct __mavlink_set_cam_shutter_t -{ - float gain; ///< Camera gain - uint16_t interval; ///< Shutter interval, in microseconds - uint16_t exposure; ///< Exposure time, in microseconds - uint8_t cam_no; ///< Camera id - uint8_t cam_mode; ///< Camera mode: 0 = auto, 1 = manual - uint8_t trigger_pin; ///< Trigger pin, 0-3 for PtGrey FireFly -} mavlink_set_cam_shutter_t; - -#define MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN 11 -#define MAVLINK_MSG_ID_151_LEN 11 - -#define MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC 108 -#define MAVLINK_MSG_ID_151_CRC 108 - - - -#define MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER { \ - "SET_CAM_SHUTTER", \ - 6, \ - { { "gain", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_cam_shutter_t, gain) }, \ - { "interval", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_set_cam_shutter_t, interval) }, \ - { "exposure", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_set_cam_shutter_t, exposure) }, \ - { "cam_no", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_set_cam_shutter_t, cam_no) }, \ - { "cam_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_set_cam_shutter_t, cam_mode) }, \ - { "trigger_pin", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_set_cam_shutter_t, trigger_pin) }, \ - } \ -} - - -/** - * @brief Pack a set_cam_shutter message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param cam_no Camera id - * @param cam_mode Camera mode: 0 = auto, 1 = manual - * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly - * @param interval Shutter interval, in microseconds - * @param exposure Exposure time, in microseconds - * @param gain Camera gain - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_cam_shutter_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN]; - _mav_put_float(buf, 0, gain); - _mav_put_uint16_t(buf, 4, interval); - _mav_put_uint16_t(buf, 6, exposure); - _mav_put_uint8_t(buf, 8, cam_no); - _mav_put_uint8_t(buf, 9, cam_mode); - _mav_put_uint8_t(buf, 10, trigger_pin); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#else - mavlink_set_cam_shutter_t packet; - packet.gain = gain; - packet.interval = interval; - packet.exposure = exposure; - packet.cam_no = cam_no; - packet.cam_mode = cam_mode; - packet.trigger_pin = trigger_pin; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#endif -} - -/** - * @brief Pack a set_cam_shutter message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param cam_no Camera id - * @param cam_mode Camera mode: 0 = auto, 1 = manual - * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly - * @param interval Shutter interval, in microseconds - * @param exposure Exposure time, in microseconds - * @param gain Camera gain - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_cam_shutter_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t cam_no,uint8_t cam_mode,uint8_t trigger_pin,uint16_t interval,uint16_t exposure,float gain) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN]; - _mav_put_float(buf, 0, gain); - _mav_put_uint16_t(buf, 4, interval); - _mav_put_uint16_t(buf, 6, exposure); - _mav_put_uint8_t(buf, 8, cam_no); - _mav_put_uint8_t(buf, 9, cam_mode); - _mav_put_uint8_t(buf, 10, trigger_pin); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#else - mavlink_set_cam_shutter_t packet; - packet.gain = gain; - packet.interval = interval; - packet.exposure = exposure; - packet.cam_no = cam_no; - packet.cam_mode = cam_mode; - packet.trigger_pin = trigger_pin; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_CAM_SHUTTER; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#endif -} - -/** - * @brief Encode a set_cam_shutter struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_cam_shutter C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_cam_shutter_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter) -{ - return mavlink_msg_set_cam_shutter_pack(system_id, component_id, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain); -} - -/** - * @brief Encode a set_cam_shutter struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_cam_shutter C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_cam_shutter_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_cam_shutter_t* set_cam_shutter) -{ - return mavlink_msg_set_cam_shutter_pack_chan(system_id, component_id, chan, msg, set_cam_shutter->cam_no, set_cam_shutter->cam_mode, set_cam_shutter->trigger_pin, set_cam_shutter->interval, set_cam_shutter->exposure, set_cam_shutter->gain); -} - -/** - * @brief Send a set_cam_shutter message - * @param chan MAVLink channel to send the message - * - * @param cam_no Camera id - * @param cam_mode Camera mode: 0 = auto, 1 = manual - * @param trigger_pin Trigger pin, 0-3 for PtGrey FireFly - * @param interval Shutter interval, in microseconds - * @param exposure Exposure time, in microseconds - * @param gain Camera gain - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_cam_shutter_send(mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN]; - _mav_put_float(buf, 0, gain); - _mav_put_uint16_t(buf, 4, interval); - _mav_put_uint16_t(buf, 6, exposure); - _mav_put_uint8_t(buf, 8, cam_no); - _mav_put_uint8_t(buf, 9, cam_mode); - _mav_put_uint8_t(buf, 10, trigger_pin); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#endif -#else - mavlink_set_cam_shutter_t packet; - packet.gain = gain; - packet.interval = interval; - packet.exposure = exposure; - packet.cam_no = cam_no; - packet.cam_mode = cam_mode; - packet.trigger_pin = trigger_pin; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)&packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)&packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_cam_shutter_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cam_no, uint8_t cam_mode, uint8_t trigger_pin, uint16_t interval, uint16_t exposure, float gain) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, gain); - _mav_put_uint16_t(buf, 4, interval); - _mav_put_uint16_t(buf, 6, exposure); - _mav_put_uint8_t(buf, 8, cam_no); - _mav_put_uint8_t(buf, 9, cam_mode); - _mav_put_uint8_t(buf, 10, trigger_pin); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, buf, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#endif -#else - mavlink_set_cam_shutter_t *packet = (mavlink_set_cam_shutter_t *)msgbuf; - packet->gain = gain; - packet->interval = interval; - packet->exposure = exposure; - packet->cam_no = cam_no; - packet->cam_mode = cam_mode; - packet->trigger_pin = trigger_pin; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN, MAVLINK_MSG_ID_SET_CAM_SHUTTER_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_CAM_SHUTTER, (const char *)packet, MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_CAM_SHUTTER UNPACKING - - -/** - * @brief Get field cam_no from set_cam_shutter message - * - * @return Camera id - */ -static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_no(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 8); -} - -/** - * @brief Get field cam_mode from set_cam_shutter message - * - * @return Camera mode: 0 = auto, 1 = manual - */ -static inline uint8_t mavlink_msg_set_cam_shutter_get_cam_mode(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 9); -} - -/** - * @brief Get field trigger_pin from set_cam_shutter message - * - * @return Trigger pin, 0-3 for PtGrey FireFly - */ -static inline uint8_t mavlink_msg_set_cam_shutter_get_trigger_pin(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field interval from set_cam_shutter message - * - * @return Shutter interval, in microseconds - */ -static inline uint16_t mavlink_msg_set_cam_shutter_get_interval(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field exposure from set_cam_shutter message - * - * @return Exposure time, in microseconds - */ -static inline uint16_t mavlink_msg_set_cam_shutter_get_exposure(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field gain from set_cam_shutter message - * - * @return Camera gain - */ -static inline float mavlink_msg_set_cam_shutter_get_gain(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Decode a set_cam_shutter message into a struct - * - * @param msg The message to decode - * @param set_cam_shutter C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_cam_shutter_decode(const mavlink_message_t* msg, mavlink_set_cam_shutter_t* set_cam_shutter) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_cam_shutter->gain = mavlink_msg_set_cam_shutter_get_gain(msg); - set_cam_shutter->interval = mavlink_msg_set_cam_shutter_get_interval(msg); - set_cam_shutter->exposure = mavlink_msg_set_cam_shutter_get_exposure(msg); - set_cam_shutter->cam_no = mavlink_msg_set_cam_shutter_get_cam_no(msg); - set_cam_shutter->cam_mode = mavlink_msg_set_cam_shutter_get_cam_mode(msg); - set_cam_shutter->trigger_pin = mavlink_msg_set_cam_shutter_get_trigger_pin(msg); -#else - memcpy(set_cam_shutter, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_CAM_SHUTTER_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h deleted file mode 100644 index c4e4fc19a..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_set_position_control_offset.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE SET_POSITION_CONTROL_OFFSET PACKING - -#define MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET 160 - -typedef struct __mavlink_set_position_control_offset_t -{ - float x; ///< x position offset - float y; ///< y position offset - float z; ///< z position offset - float yaw; ///< yaw orientation offset in radians, 0 = NORTH - uint8_t target_system; ///< System ID - uint8_t target_component; ///< Component ID -} mavlink_set_position_control_offset_t; - -#define MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN 18 -#define MAVLINK_MSG_ID_160_LEN 18 - -#define MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC 22 -#define MAVLINK_MSG_ID_160_CRC 22 - - - -#define MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET { \ - "SET_POSITION_CONTROL_OFFSET", \ - 6, \ - { { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_position_control_offset_t, x) }, \ - { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_position_control_offset_t, y) }, \ - { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_position_control_offset_t, z) }, \ - { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_position_control_offset_t, yaw) }, \ - { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_position_control_offset_t, target_system) }, \ - { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_position_control_offset_t, target_component) }, \ - } \ -} - - -/** - * @brief Pack a set_position_control_offset message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system System ID - * @param target_component Component ID - * @param x x position offset - * @param y y position offset - * @param z z position offset - * @param yaw yaw orientation offset in radians, 0 = NORTH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_control_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#else - mavlink_set_position_control_offset_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#endif -} - -/** - * @brief Pack a set_position_control_offset message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system System ID - * @param target_component Component ID - * @param x x position offset - * @param y y position offset - * @param z z position offset - * @param yaw yaw orientation offset in radians, 0 = NORTH - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_set_position_control_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system,uint8_t target_component,float x,float y,float z,float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#else - mavlink_set_position_control_offset_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.target_system = target_system; - packet.target_component = target_component; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#endif -} - -/** - * @brief Encode a set_position_control_offset struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param set_position_control_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_control_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_position_control_offset_t* set_position_control_offset) -{ - return mavlink_msg_set_position_control_offset_pack(system_id, component_id, msg, set_position_control_offset->target_system, set_position_control_offset->target_component, set_position_control_offset->x, set_position_control_offset->y, set_position_control_offset->z, set_position_control_offset->yaw); -} - -/** - * @brief Encode a set_position_control_offset struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param set_position_control_offset C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_set_position_control_offset_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_position_control_offset_t* set_position_control_offset) -{ - return mavlink_msg_set_position_control_offset_pack_chan(system_id, component_id, chan, msg, set_position_control_offset->target_system, set_position_control_offset->target_component, set_position_control_offset->x, set_position_control_offset->y, set_position_control_offset->z, set_position_control_offset->yaw); -} - -/** - * @brief Send a set_position_control_offset message - * @param chan MAVLink channel to send the message - * - * @param target_system System ID - * @param target_component Component ID - * @param x x position offset - * @param y y position offset - * @param z z position offset - * @param yaw yaw orientation offset in radians, 0 = NORTH - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_set_position_control_offset_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN]; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#endif -#else - mavlink_set_position_control_offset_t packet; - packet.x = x; - packet.y = y; - packet.z = z; - packet.yaw = yaw; - packet.target_system = target_system; - packet.target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_set_position_control_offset_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, x); - _mav_put_float(buf, 4, y); - _mav_put_float(buf, 8, z); - _mav_put_float(buf, 12, yaw); - _mav_put_uint8_t(buf, 16, target_system); - _mav_put_uint8_t(buf, 17, target_component); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, buf, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#endif -#else - mavlink_set_position_control_offset_t *packet = (mavlink_set_position_control_offset_t *)msgbuf; - packet->x = x; - packet->y = y; - packet->z = z; - packet->yaw = yaw; - packet->target_system = target_system; - packet->target_component = target_component; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SET_POSITION_CONTROL_OFFSET UNPACKING - - -/** - * @brief Get field target_system from set_position_control_offset message - * - * @return System ID - */ -static inline uint8_t mavlink_msg_set_position_control_offset_get_target_system(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 16); -} - -/** - * @brief Get field target_component from set_position_control_offset message - * - * @return Component ID - */ -static inline uint8_t mavlink_msg_set_position_control_offset_get_target_component(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 17); -} - -/** - * @brief Get field x from set_position_control_offset message - * - * @return x position offset - */ -static inline float mavlink_msg_set_position_control_offset_get_x(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field y from set_position_control_offset message - * - * @return y position offset - */ -static inline float mavlink_msg_set_position_control_offset_get_y(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field z from set_position_control_offset message - * - * @return z position offset - */ -static inline float mavlink_msg_set_position_control_offset_get_z(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Get field yaw from set_position_control_offset message - * - * @return yaw orientation offset in radians, 0 = NORTH - */ -static inline float mavlink_msg_set_position_control_offset_get_yaw(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 12); -} - -/** - * @brief Decode a set_position_control_offset message into a struct - * - * @param msg The message to decode - * @param set_position_control_offset C-struct to decode the message contents into - */ -static inline void mavlink_msg_set_position_control_offset_decode(const mavlink_message_t* msg, mavlink_set_position_control_offset_t* set_position_control_offset) -{ -#if MAVLINK_NEED_BYTE_SWAP - set_position_control_offset->x = mavlink_msg_set_position_control_offset_get_x(msg); - set_position_control_offset->y = mavlink_msg_set_position_control_offset_get_y(msg); - set_position_control_offset->z = mavlink_msg_set_position_control_offset_get_z(msg); - set_position_control_offset->yaw = mavlink_msg_set_position_control_offset_get_yaw(msg); - set_position_control_offset->target_system = mavlink_msg_set_position_control_offset_get_target_system(msg); - set_position_control_offset->target_component = mavlink_msg_set_position_control_offset_get_target_component(msg); -#else - memcpy(set_position_control_offset, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SET_POSITION_CONTROL_OFFSET_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h deleted file mode 100644 index d71a2ed2e..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_command.h +++ /dev/null @@ -1,281 +0,0 @@ -// MESSAGE WATCHDOG_COMMAND PACKING - -#define MAVLINK_MSG_ID_WATCHDOG_COMMAND 183 - -typedef struct __mavlink_watchdog_command_t -{ - uint16_t watchdog_id; ///< Watchdog ID - uint16_t process_id; ///< Process ID - uint8_t target_system_id; ///< Target system ID - uint8_t command_id; ///< Command ID -} mavlink_watchdog_command_t; - -#define MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN 6 -#define MAVLINK_MSG_ID_183_LEN 6 - -#define MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC 162 -#define MAVLINK_MSG_ID_183_CRC 162 - - - -#define MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND { \ - "WATCHDOG_COMMAND", \ - 4, \ - { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_command_t, watchdog_id) }, \ - { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_command_t, process_id) }, \ - { "target_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_watchdog_command_t, target_system_id) }, \ - { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_watchdog_command_t, command_id) }, \ - } \ -} - - -/** - * @brief Pack a watchdog_command message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target_system_id Target system ID - * @param watchdog_id Watchdog ID - * @param process_id Process ID - * @param command_id Command ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_watchdog_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_uint8_t(buf, 4, target_system_id); - _mav_put_uint8_t(buf, 5, command_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#else - mavlink_watchdog_command_t packet; - packet.watchdog_id = watchdog_id; - packet.process_id = process_id; - packet.target_system_id = target_system_id; - packet.command_id = command_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#endif -} - -/** - * @brief Pack a watchdog_command message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target_system_id Target system ID - * @param watchdog_id Watchdog ID - * @param process_id Process ID - * @param command_id Command ID - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_watchdog_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target_system_id,uint16_t watchdog_id,uint16_t process_id,uint8_t command_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_uint8_t(buf, 4, target_system_id); - _mav_put_uint8_t(buf, 5, command_id); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#else - mavlink_watchdog_command_t packet; - packet.watchdog_id = watchdog_id; - packet.process_id = process_id; - packet.target_system_id = target_system_id; - packet.command_id = command_id; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WATCHDOG_COMMAND; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#endif -} - -/** - * @brief Encode a watchdog_command struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param watchdog_command C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_watchdog_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command) -{ - return mavlink_msg_watchdog_command_pack(system_id, component_id, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id); -} - -/** - * @brief Encode a watchdog_command struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param watchdog_command C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_watchdog_command_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_watchdog_command_t* watchdog_command) -{ - return mavlink_msg_watchdog_command_pack_chan(system_id, component_id, chan, msg, watchdog_command->target_system_id, watchdog_command->watchdog_id, watchdog_command->process_id, watchdog_command->command_id); -} - -/** - * @brief Send a watchdog_command message - * @param chan MAVLink channel to send the message - * - * @param target_system_id Target system ID - * @param watchdog_id Watchdog ID - * @param process_id Process ID - * @param command_id Command ID - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_watchdog_command_send(mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_uint8_t(buf, 4, target_system_id); - _mav_put_uint8_t(buf, 5, command_id); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#endif -#else - mavlink_watchdog_command_t packet; - packet.watchdog_id = watchdog_id; - packet.process_id = process_id; - packet.target_system_id = target_system_id; - packet.command_id = command_id; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_watchdog_command_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system_id, uint16_t watchdog_id, uint16_t process_id, uint8_t command_id) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_id); - _mav_put_uint8_t(buf, 4, target_system_id); - _mav_put_uint8_t(buf, 5, command_id); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, buf, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#endif -#else - mavlink_watchdog_command_t *packet = (mavlink_watchdog_command_t *)msgbuf; - packet->watchdog_id = watchdog_id; - packet->process_id = process_id; - packet->target_system_id = target_system_id; - packet->command_id = command_id; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN, MAVLINK_MSG_ID_WATCHDOG_COMMAND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_COMMAND, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE WATCHDOG_COMMAND UNPACKING - - -/** - * @brief Get field target_system_id from watchdog_command message - * - * @return Target system ID - */ -static inline uint8_t mavlink_msg_watchdog_command_get_target_system_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field watchdog_id from watchdog_command message - * - * @return Watchdog ID - */ -static inline uint16_t mavlink_msg_watchdog_command_get_watchdog_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field process_id from watchdog_command message - * - * @return Process ID - */ -static inline uint16_t mavlink_msg_watchdog_command_get_process_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Get field command_id from watchdog_command message - * - * @return Command ID - */ -static inline uint8_t mavlink_msg_watchdog_command_get_command_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 5); -} - -/** - * @brief Decode a watchdog_command message into a struct - * - * @param msg The message to decode - * @param watchdog_command C-struct to decode the message contents into - */ -static inline void mavlink_msg_watchdog_command_decode(const mavlink_message_t* msg, mavlink_watchdog_command_t* watchdog_command) -{ -#if MAVLINK_NEED_BYTE_SWAP - watchdog_command->watchdog_id = mavlink_msg_watchdog_command_get_watchdog_id(msg); - watchdog_command->process_id = mavlink_msg_watchdog_command_get_process_id(msg); - watchdog_command->target_system_id = mavlink_msg_watchdog_command_get_target_system_id(msg); - watchdog_command->command_id = mavlink_msg_watchdog_command_get_command_id(msg); -#else - memcpy(watchdog_command, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WATCHDOG_COMMAND_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h deleted file mode 100644 index a8e49b642..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_heartbeat.h +++ /dev/null @@ -1,233 +0,0 @@ -// MESSAGE WATCHDOG_HEARTBEAT PACKING - -#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT 180 - -typedef struct __mavlink_watchdog_heartbeat_t -{ - uint16_t watchdog_id; ///< Watchdog ID - uint16_t process_count; ///< Number of processes -} mavlink_watchdog_heartbeat_t; - -#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN 4 -#define MAVLINK_MSG_ID_180_LEN 4 - -#define MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC 153 -#define MAVLINK_MSG_ID_180_CRC 153 - - - -#define MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT { \ - "WATCHDOG_HEARTBEAT", \ - 2, \ - { { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_watchdog_heartbeat_t, watchdog_id) }, \ - { "process_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_watchdog_heartbeat_t, process_count) }, \ - } \ -} - - -/** - * @brief Pack a watchdog_heartbeat message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param watchdog_id Watchdog ID - * @param process_count Number of processes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_watchdog_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t watchdog_id, uint16_t process_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_count); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#else - mavlink_watchdog_heartbeat_t packet; - packet.watchdog_id = watchdog_id; - packet.process_count = process_count; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#endif -} - -/** - * @brief Pack a watchdog_heartbeat message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param watchdog_id Watchdog ID - * @param process_count Number of processes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_watchdog_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t watchdog_id,uint16_t process_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_count); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#else - mavlink_watchdog_heartbeat_t packet; - packet.watchdog_id = watchdog_id; - packet.process_count = process_count; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#endif -} - -/** - * @brief Encode a watchdog_heartbeat struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param watchdog_heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_watchdog_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat) -{ - return mavlink_msg_watchdog_heartbeat_pack(system_id, component_id, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count); -} - -/** - * @brief Encode a watchdog_heartbeat struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param watchdog_heartbeat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_watchdog_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_watchdog_heartbeat_t* watchdog_heartbeat) -{ - return mavlink_msg_watchdog_heartbeat_pack_chan(system_id, component_id, chan, msg, watchdog_heartbeat->watchdog_id, watchdog_heartbeat->process_count); -} - -/** - * @brief Send a watchdog_heartbeat message - * @param chan MAVLink channel to send the message - * - * @param watchdog_id Watchdog ID - * @param process_count Number of processes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_watchdog_heartbeat_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN]; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_count); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#endif -#else - mavlink_watchdog_heartbeat_t packet; - packet.watchdog_id = watchdog_id; - packet.process_count = process_count; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_watchdog_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_count) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint16_t(buf, 0, watchdog_id); - _mav_put_uint16_t(buf, 2, process_count); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, buf, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#endif -#else - mavlink_watchdog_heartbeat_t *packet = (mavlink_watchdog_heartbeat_t *)msgbuf; - packet->watchdog_id = watchdog_id; - packet->process_count = process_count; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE WATCHDOG_HEARTBEAT UNPACKING - - -/** - * @brief Get field watchdog_id from watchdog_heartbeat message - * - * @return Watchdog ID - */ -static inline uint16_t mavlink_msg_watchdog_heartbeat_get_watchdog_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 0); -} - -/** - * @brief Get field process_count from watchdog_heartbeat message - * - * @return Number of processes - */ -static inline uint16_t mavlink_msg_watchdog_heartbeat_get_process_count(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 2); -} - -/** - * @brief Decode a watchdog_heartbeat message into a struct - * - * @param msg The message to decode - * @param watchdog_heartbeat C-struct to decode the message contents into - */ -static inline void mavlink_msg_watchdog_heartbeat_decode(const mavlink_message_t* msg, mavlink_watchdog_heartbeat_t* watchdog_heartbeat) -{ -#if MAVLINK_NEED_BYTE_SWAP - watchdog_heartbeat->watchdog_id = mavlink_msg_watchdog_heartbeat_get_watchdog_id(msg); - watchdog_heartbeat->process_count = mavlink_msg_watchdog_heartbeat_get_process_count(msg); -#else - memcpy(watchdog_heartbeat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WATCHDOG_HEARTBEAT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h deleted file mode 100644 index a5e0cc67e..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_info.h +++ /dev/null @@ -1,298 +0,0 @@ -// MESSAGE WATCHDOG_PROCESS_INFO PACKING - -#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO 181 - -typedef struct __mavlink_watchdog_process_info_t -{ - int32_t timeout; ///< Timeout (seconds) - uint16_t watchdog_id; ///< Watchdog ID - uint16_t process_id; ///< Process ID - char name[100]; ///< Process name - char arguments[147]; ///< Process arguments -} mavlink_watchdog_process_info_t; - -#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN 255 -#define MAVLINK_MSG_ID_181_LEN 255 - -#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC 16 -#define MAVLINK_MSG_ID_181_CRC 16 - -#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_NAME_LEN 100 -#define MAVLINK_MSG_WATCHDOG_PROCESS_INFO_FIELD_ARGUMENTS_LEN 147 - -#define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO { \ - "WATCHDOG_PROCESS_INFO", \ - 5, \ - { { "timeout", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_watchdog_process_info_t, timeout) }, \ - { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_watchdog_process_info_t, watchdog_id) }, \ - { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_watchdog_process_info_t, process_id) }, \ - { "name", NULL, MAVLINK_TYPE_CHAR, 100, 8, offsetof(mavlink_watchdog_process_info_t, name) }, \ - { "arguments", NULL, MAVLINK_TYPE_CHAR, 147, 108, offsetof(mavlink_watchdog_process_info_t, arguments) }, \ - } \ -} - - -/** - * @brief Pack a watchdog_process_info message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param watchdog_id Watchdog ID - * @param process_id Process ID - * @param name Process name - * @param arguments Process arguments - * @param timeout Timeout (seconds) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_watchdog_process_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN]; - _mav_put_int32_t(buf, 0, timeout); - _mav_put_uint16_t(buf, 4, watchdog_id); - _mav_put_uint16_t(buf, 6, process_id); - _mav_put_char_array(buf, 8, name, 100); - _mav_put_char_array(buf, 108, arguments, 147); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#else - mavlink_watchdog_process_info_t packet; - packet.timeout = timeout; - packet.watchdog_id = watchdog_id; - packet.process_id = process_id; - mav_array_memcpy(packet.name, name, sizeof(char)*100); - mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#endif -} - -/** - * @brief Pack a watchdog_process_info message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param watchdog_id Watchdog ID - * @param process_id Process ID - * @param name Process name - * @param arguments Process arguments - * @param timeout Timeout (seconds) - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_watchdog_process_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t watchdog_id,uint16_t process_id,const char *name,const char *arguments,int32_t timeout) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN]; - _mav_put_int32_t(buf, 0, timeout); - _mav_put_uint16_t(buf, 4, watchdog_id); - _mav_put_uint16_t(buf, 6, process_id); - _mav_put_char_array(buf, 8, name, 100); - _mav_put_char_array(buf, 108, arguments, 147); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#else - mavlink_watchdog_process_info_t packet; - packet.timeout = timeout; - packet.watchdog_id = watchdog_id; - packet.process_id = process_id; - mav_array_memcpy(packet.name, name, sizeof(char)*100); - mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#endif -} - -/** - * @brief Encode a watchdog_process_info struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param watchdog_process_info C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_watchdog_process_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info) -{ - return mavlink_msg_watchdog_process_info_pack(system_id, component_id, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout); -} - -/** - * @brief Encode a watchdog_process_info struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param watchdog_process_info C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_watchdog_process_info_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_watchdog_process_info_t* watchdog_process_info) -{ - return mavlink_msg_watchdog_process_info_pack_chan(system_id, component_id, chan, msg, watchdog_process_info->watchdog_id, watchdog_process_info->process_id, watchdog_process_info->name, watchdog_process_info->arguments, watchdog_process_info->timeout); -} - -/** - * @brief Send a watchdog_process_info message - * @param chan MAVLink channel to send the message - * - * @param watchdog_id Watchdog ID - * @param process_id Process ID - * @param name Process name - * @param arguments Process arguments - * @param timeout Timeout (seconds) - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_watchdog_process_info_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN]; - _mav_put_int32_t(buf, 0, timeout); - _mav_put_uint16_t(buf, 4, watchdog_id); - _mav_put_uint16_t(buf, 6, process_id); - _mav_put_char_array(buf, 8, name, 100); - _mav_put_char_array(buf, 108, arguments, 147); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#endif -#else - mavlink_watchdog_process_info_t packet; - packet.timeout = timeout; - packet.watchdog_id = watchdog_id; - packet.process_id = process_id; - mav_array_memcpy(packet.name, name, sizeof(char)*100); - mav_array_memcpy(packet.arguments, arguments, sizeof(char)*147); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_watchdog_process_info_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, const char *name, const char *arguments, int32_t timeout) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, timeout); - _mav_put_uint16_t(buf, 4, watchdog_id); - _mav_put_uint16_t(buf, 6, process_id); - _mav_put_char_array(buf, 8, name, 100); - _mav_put_char_array(buf, 108, arguments, 147); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#endif -#else - mavlink_watchdog_process_info_t *packet = (mavlink_watchdog_process_info_t *)msgbuf; - packet->timeout = timeout; - packet->watchdog_id = watchdog_id; - packet->process_id = process_id; - mav_array_memcpy(packet->name, name, sizeof(char)*100); - mav_array_memcpy(packet->arguments, arguments, sizeof(char)*147); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE WATCHDOG_PROCESS_INFO UNPACKING - - -/** - * @brief Get field watchdog_id from watchdog_process_info message - * - * @return Watchdog ID - */ -static inline uint16_t mavlink_msg_watchdog_process_info_get_watchdog_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field process_id from watchdog_process_info message - * - * @return Process ID - */ -static inline uint16_t mavlink_msg_watchdog_process_info_get_process_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field name from watchdog_process_info message - * - * @return Process name - */ -static inline uint16_t mavlink_msg_watchdog_process_info_get_name(const mavlink_message_t* msg, char *name) -{ - return _MAV_RETURN_char_array(msg, name, 100, 8); -} - -/** - * @brief Get field arguments from watchdog_process_info message - * - * @return Process arguments - */ -static inline uint16_t mavlink_msg_watchdog_process_info_get_arguments(const mavlink_message_t* msg, char *arguments) -{ - return _MAV_RETURN_char_array(msg, arguments, 147, 108); -} - -/** - * @brief Get field timeout from watchdog_process_info message - * - * @return Timeout (seconds) - */ -static inline int32_t mavlink_msg_watchdog_process_info_get_timeout(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Decode a watchdog_process_info message into a struct - * - * @param msg The message to decode - * @param watchdog_process_info C-struct to decode the message contents into - */ -static inline void mavlink_msg_watchdog_process_info_decode(const mavlink_message_t* msg, mavlink_watchdog_process_info_t* watchdog_process_info) -{ -#if MAVLINK_NEED_BYTE_SWAP - watchdog_process_info->timeout = mavlink_msg_watchdog_process_info_get_timeout(msg); - watchdog_process_info->watchdog_id = mavlink_msg_watchdog_process_info_get_watchdog_id(msg); - watchdog_process_info->process_id = mavlink_msg_watchdog_process_info_get_process_id(msg); - mavlink_msg_watchdog_process_info_get_name(msg, watchdog_process_info->name); - mavlink_msg_watchdog_process_info_get_arguments(msg, watchdog_process_info->arguments); -#else - memcpy(watchdog_process_info, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WATCHDOG_PROCESS_INFO_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h b/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h deleted file mode 100644 index 15c9598e4..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/mavlink_msg_watchdog_process_status.h +++ /dev/null @@ -1,329 +0,0 @@ -// MESSAGE WATCHDOG_PROCESS_STATUS PACKING - -#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS 182 - -typedef struct __mavlink_watchdog_process_status_t -{ - int32_t pid; ///< PID - uint16_t watchdog_id; ///< Watchdog ID - uint16_t process_id; ///< Process ID - uint16_t crashes; ///< Number of crashes - uint8_t state; ///< Is running / finished / suspended / crashed - uint8_t muted; ///< Is muted -} mavlink_watchdog_process_status_t; - -#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN 12 -#define MAVLINK_MSG_ID_182_LEN 12 - -#define MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC 29 -#define MAVLINK_MSG_ID_182_CRC 29 - - - -#define MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS { \ - "WATCHDOG_PROCESS_STATUS", \ - 6, \ - { { "pid", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_watchdog_process_status_t, pid) }, \ - { "watchdog_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_watchdog_process_status_t, watchdog_id) }, \ - { "process_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_watchdog_process_status_t, process_id) }, \ - { "crashes", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_watchdog_process_status_t, crashes) }, \ - { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_watchdog_process_status_t, state) }, \ - { "muted", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_watchdog_process_status_t, muted) }, \ - } \ -} - - -/** - * @brief Pack a watchdog_process_status message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param watchdog_id Watchdog ID - * @param process_id Process ID - * @param state Is running / finished / suspended / crashed - * @param muted Is muted - * @param pid PID - * @param crashes Number of crashes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_watchdog_process_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN]; - _mav_put_int32_t(buf, 0, pid); - _mav_put_uint16_t(buf, 4, watchdog_id); - _mav_put_uint16_t(buf, 6, process_id); - _mav_put_uint16_t(buf, 8, crashes); - _mav_put_uint8_t(buf, 10, state); - _mav_put_uint8_t(buf, 11, muted); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#else - mavlink_watchdog_process_status_t packet; - packet.pid = pid; - packet.watchdog_id = watchdog_id; - packet.process_id = process_id; - packet.crashes = crashes; - packet.state = state; - packet.muted = muted; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#endif -} - -/** - * @brief Pack a watchdog_process_status message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param watchdog_id Watchdog ID - * @param process_id Process ID - * @param state Is running / finished / suspended / crashed - * @param muted Is muted - * @param pid PID - * @param crashes Number of crashes - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_watchdog_process_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint16_t watchdog_id,uint16_t process_id,uint8_t state,uint8_t muted,int32_t pid,uint16_t crashes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN]; - _mav_put_int32_t(buf, 0, pid); - _mav_put_uint16_t(buf, 4, watchdog_id); - _mav_put_uint16_t(buf, 6, process_id); - _mav_put_uint16_t(buf, 8, crashes); - _mav_put_uint8_t(buf, 10, state); - _mav_put_uint8_t(buf, 11, muted); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#else - mavlink_watchdog_process_status_t packet; - packet.pid = pid; - packet.watchdog_id = watchdog_id; - packet.process_id = process_id; - packet.crashes = crashes; - packet.state = state; - packet.muted = muted; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#endif -} - -/** - * @brief Encode a watchdog_process_status struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param watchdog_process_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_watchdog_process_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status) -{ - return mavlink_msg_watchdog_process_status_pack(system_id, component_id, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes); -} - -/** - * @brief Encode a watchdog_process_status struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param watchdog_process_status C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_watchdog_process_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_watchdog_process_status_t* watchdog_process_status) -{ - return mavlink_msg_watchdog_process_status_pack_chan(system_id, component_id, chan, msg, watchdog_process_status->watchdog_id, watchdog_process_status->process_id, watchdog_process_status->state, watchdog_process_status->muted, watchdog_process_status->pid, watchdog_process_status->crashes); -} - -/** - * @brief Send a watchdog_process_status message - * @param chan MAVLink channel to send the message - * - * @param watchdog_id Watchdog ID - * @param process_id Process ID - * @param state Is running / finished / suspended / crashed - * @param muted Is muted - * @param pid PID - * @param crashes Number of crashes - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_watchdog_process_status_send(mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN]; - _mav_put_int32_t(buf, 0, pid); - _mav_put_uint16_t(buf, 4, watchdog_id); - _mav_put_uint16_t(buf, 6, process_id); - _mav_put_uint16_t(buf, 8, crashes); - _mav_put_uint8_t(buf, 10, state); - _mav_put_uint8_t(buf, 11, muted); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#endif -#else - mavlink_watchdog_process_status_t packet; - packet.pid = pid; - packet.watchdog_id = watchdog_id; - packet.process_id = process_id; - packet.crashes = crashes; - packet.state = state; - packet.muted = muted; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_watchdog_process_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t watchdog_id, uint16_t process_id, uint8_t state, uint8_t muted, int32_t pid, uint16_t crashes) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, pid); - _mav_put_uint16_t(buf, 4, watchdog_id); - _mav_put_uint16_t(buf, 6, process_id); - _mav_put_uint16_t(buf, 8, crashes); - _mav_put_uint8_t(buf, 10, state); - _mav_put_uint8_t(buf, 11, muted); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, buf, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#endif -#else - mavlink_watchdog_process_status_t *packet = (mavlink_watchdog_process_status_t *)msgbuf; - packet->pid = pid; - packet->watchdog_id = watchdog_id; - packet->process_id = process_id; - packet->crashes = crashes; - packet->state = state; - packet->muted = muted; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS, (const char *)packet, MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE WATCHDOG_PROCESS_STATUS UNPACKING - - -/** - * @brief Get field watchdog_id from watchdog_process_status message - * - * @return Watchdog ID - */ -static inline uint16_t mavlink_msg_watchdog_process_status_get_watchdog_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 4); -} - -/** - * @brief Get field process_id from watchdog_process_status message - * - * @return Process ID - */ -static inline uint16_t mavlink_msg_watchdog_process_status_get_process_id(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 6); -} - -/** - * @brief Get field state from watchdog_process_status message - * - * @return Is running / finished / suspended / crashed - */ -static inline uint8_t mavlink_msg_watchdog_process_status_get_state(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 10); -} - -/** - * @brief Get field muted from watchdog_process_status message - * - * @return Is muted - */ -static inline uint8_t mavlink_msg_watchdog_process_status_get_muted(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field pid from watchdog_process_status message - * - * @return PID - */ -static inline int32_t mavlink_msg_watchdog_process_status_get_pid(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field crashes from watchdog_process_status message - * - * @return Number of crashes - */ -static inline uint16_t mavlink_msg_watchdog_process_status_get_crashes(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 8); -} - -/** - * @brief Decode a watchdog_process_status message into a struct - * - * @param msg The message to decode - * @param watchdog_process_status C-struct to decode the message contents into - */ -static inline void mavlink_msg_watchdog_process_status_decode(const mavlink_message_t* msg, mavlink_watchdog_process_status_t* watchdog_process_status) -{ -#if MAVLINK_NEED_BYTE_SWAP - watchdog_process_status->pid = mavlink_msg_watchdog_process_status_get_pid(msg); - watchdog_process_status->watchdog_id = mavlink_msg_watchdog_process_status_get_watchdog_id(msg); - watchdog_process_status->process_id = mavlink_msg_watchdog_process_status_get_process_id(msg); - watchdog_process_status->crashes = mavlink_msg_watchdog_process_status_get_crashes(msg); - watchdog_process_status->state = mavlink_msg_watchdog_process_status_get_state(msg); - watchdog_process_status->muted = mavlink_msg_watchdog_process_status_get_muted(msg); -#else - memcpy(watchdog_process_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_WATCHDOG_PROCESS_STATUS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h deleted file mode 100644 index a624a2579..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h +++ /dev/null @@ -1,136 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from pixhawk.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef PIXHAWK_H -#define PIXHAWK_H - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 11, 52, 1, 92, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 26, 16, 0, 0, 0, 0, 0, 0, 0, 4, 255, 12, 6, 0, 0, 0, 0, 0, 0, 106, 43, 55, 0, 0, 53, 0, 0, 0, 0, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 108, 86, 95, 224, 0, 0, 0, 0, 0, 22, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 249, 182, 0, 0, 0, 0, 0, 0, 0, 153, 16, 29, 162, 0, 0, 0, 0, 0, 0, 90, 95, 36, 0, 0, 88, 0, 0, 0, 0, 254, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} -#endif - -#ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_CAM_SHUTTER, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGERED, MAVLINK_MESSAGE_INFO_IMAGE_TRIGGER_CONTROL, MAVLINK_MESSAGE_INFO_IMAGE_AVAILABLE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_POSITION_CONTROL_OFFSET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_POSITION_CONTROL_SETPOINT, MAVLINK_MESSAGE_INFO_MARKER, MAVLINK_MESSAGE_INFO_RAW_AUX, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_WATCHDOG_HEARTBEAT, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_INFO, MAVLINK_MESSAGE_INFO_WATCHDOG_PROCESS_STATUS, MAVLINK_MESSAGE_INFO_WATCHDOG_COMMAND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PATTERN_DETECTED, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST, MAVLINK_MESSAGE_INFO_POINT_OF_INTEREST_CONNECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BRIEF_FEATURE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ATTITUDE_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_PIXHAWK - -// ENUM DEFINITIONS - - -/** @brief Content Types for data transmission handshake */ -#ifndef HAVE_ENUM_DATA_TYPES -#define HAVE_ENUM_DATA_TYPES -enum DATA_TYPES -{ - DATA_TYPE_JPEG_IMAGE=1, /* | */ - DATA_TYPE_RAW_IMAGE=2, /* | */ - DATA_TYPE_KINECT=3, /* | */ - DATA_TYPES_ENUM_END=4, /* | */ -}; -#endif - -/** @brief */ -#ifndef HAVE_ENUM_MAV_CMD -#define HAVE_ENUM_MAV_CMD -enum MAV_CMD -{ - MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */ - MAV_CMD_NAV_ROI=80, /* 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. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to MISSION using a spline path. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */ - MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */ - MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */ - MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */ - MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */ - 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_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 sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */ - MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */ - MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */ - MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch or lat in degrees, depending on mount mode.| roll or lon in degrees depending on mount mode| yaw or alt (in meters) depending on mount mode| reserved| reserved| reserved| MAV_MOUNT_MODE enum value| */ - MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set CAM_TRIGG_DIST for this flight |Camera trigger distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_FENCE_ENABLE=207, /* Mission command to enable the geofence |enable? (0=disable, 1=enable)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_PARACHUTE=208, /* Mission command to trigger a parachute |action (0=disable, 1=enable, 2=release, for some systems see PARACHUTE_ACTION enum, not in general message set.)| Empty| Empty| Empty| Empty| Empty| Empty| */ - MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |q1 - quaternion param #1| q2 - quaternion param #2| q3 - quaternion param #3| q4 - quaternion param #4| Empty| Empty| Empty| */ - 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| Accelerometer calibration: 0: no, 1: yes| Compass/Motor interference calibration: 0: no, 1: yes| Empty| */ - MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */ - 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| */ - MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */ - MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */ - MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */ - MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */ - MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing |0:Spektrum| 0:Spektrum DSM2, 1:Spektrum DSMX| */ - MAV_CMD_ENUM_END=501, /* | */ - MAV_CMD_DO_START_SEARCH=10001, /* Starts a search |1 to arm, 0 to disarm| */ - MAV_CMD_DO_FINISH_SEARCH=10002, /* Starts a search |1 to arm, 0 to disarm| */ - MAV_CMD_NAV_SWEEP=10003, /* Starts a search |1 to arm, 0 to disarm| */ -}; -#endif - -#include "../common/common.h" - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_set_cam_shutter.h" -#include "./mavlink_msg_image_triggered.h" -#include "./mavlink_msg_image_trigger_control.h" -#include "./mavlink_msg_image_available.h" -#include "./mavlink_msg_set_position_control_offset.h" -#include "./mavlink_msg_position_control_setpoint.h" -#include "./mavlink_msg_marker.h" -#include "./mavlink_msg_raw_aux.h" -#include "./mavlink_msg_watchdog_heartbeat.h" -#include "./mavlink_msg_watchdog_process_info.h" -#include "./mavlink_msg_watchdog_process_status.h" -#include "./mavlink_msg_watchdog_command.h" -#include "./mavlink_msg_pattern_detected.h" -#include "./mavlink_msg_point_of_interest.h" -#include "./mavlink_msg_point_of_interest_connection.h" -#include "./mavlink_msg_brief_feature.h" -#include "./mavlink_msg_attitude_control.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // PIXHAWK_H diff --git a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h b/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h deleted file mode 100644 index 7556606e9..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/pixhawk.pb.h +++ /dev/null @@ -1,3663 +0,0 @@ -// Generated by the protocol buffer compiler. DO NOT EDIT! -// source: pixhawk.proto - -#ifndef PROTOBUF_pixhawk_2eproto__INCLUDED -#define PROTOBUF_pixhawk_2eproto__INCLUDED - -#include - -#include - -#if GOOGLE_PROTOBUF_VERSION < 2004000 -#error This file was generated by a newer version of protoc which is -#error incompatible with your Protocol Buffer headers. Please update -#error your headers. -#endif -#if 2004001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION -#error This file was generated by an older version of protoc which is -#error incompatible with your Protocol Buffer headers. Please -#error regenerate this file with a newer version of protoc. -#endif - -#include -#include -#include -#include -// @@protoc_insertion_point(includes) - -namespace px { - -// Internal implementation detail -- do not call these. -void protobuf_AddDesc_pixhawk_2eproto(); -void protobuf_AssignDesc_pixhawk_2eproto(); -void protobuf_ShutdownFile_pixhawk_2eproto(); - -class HeaderInfo; -class GLOverlay; -class Obstacle; -class ObstacleList; -class ObstacleMap; -class Path; -class PointCloudXYZI; -class PointCloudXYZI_PointXYZI; -class PointCloudXYZRGB; -class PointCloudXYZRGB_PointXYZRGB; -class RGBDImage; -class Waypoint; - -enum GLOverlay_CoordinateFrameType { - GLOverlay_CoordinateFrameType_GLOBAL = 0, - GLOverlay_CoordinateFrameType_LOCAL = 1 -}; -bool GLOverlay_CoordinateFrameType_IsValid(int value); -const GLOverlay_CoordinateFrameType GLOverlay_CoordinateFrameType_CoordinateFrameType_MIN = GLOverlay_CoordinateFrameType_GLOBAL; -const GLOverlay_CoordinateFrameType GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX = GLOverlay_CoordinateFrameType_LOCAL; -const int GLOverlay_CoordinateFrameType_CoordinateFrameType_ARRAYSIZE = GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX + 1; - -const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor(); -inline const ::std::string& GLOverlay_CoordinateFrameType_Name(GLOverlay_CoordinateFrameType value) { - return ::google::protobuf::internal::NameOfEnum( - GLOverlay_CoordinateFrameType_descriptor(), value); -} -inline bool GLOverlay_CoordinateFrameType_Parse( - const ::std::string& name, GLOverlay_CoordinateFrameType* value) { - return ::google::protobuf::internal::ParseNamedEnum( - GLOverlay_CoordinateFrameType_descriptor(), name, value); -} -enum GLOverlay_Mode { - GLOverlay_Mode_POINTS = 0, - GLOverlay_Mode_LINES = 1, - GLOverlay_Mode_LINE_STRIP = 2, - GLOverlay_Mode_LINE_LOOP = 3, - GLOverlay_Mode_TRIANGLES = 4, - GLOverlay_Mode_TRIANGLE_STRIP = 5, - GLOverlay_Mode_TRIANGLE_FAN = 6, - GLOverlay_Mode_QUADS = 7, - GLOverlay_Mode_QUAD_STRIP = 8, - GLOverlay_Mode_POLYGON = 9, - GLOverlay_Mode_SOLID_CIRCLE = 10, - GLOverlay_Mode_WIRE_CIRCLE = 11, - GLOverlay_Mode_SOLID_CUBE = 12, - GLOverlay_Mode_WIRE_CUBE = 13 -}; -bool GLOverlay_Mode_IsValid(int value); -const GLOverlay_Mode GLOverlay_Mode_Mode_MIN = GLOverlay_Mode_POINTS; -const GLOverlay_Mode GLOverlay_Mode_Mode_MAX = GLOverlay_Mode_WIRE_CUBE; -const int GLOverlay_Mode_Mode_ARRAYSIZE = GLOverlay_Mode_Mode_MAX + 1; - -const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor(); -inline const ::std::string& GLOverlay_Mode_Name(GLOverlay_Mode value) { - return ::google::protobuf::internal::NameOfEnum( - GLOverlay_Mode_descriptor(), value); -} -inline bool GLOverlay_Mode_Parse( - const ::std::string& name, GLOverlay_Mode* value) { - return ::google::protobuf::internal::ParseNamedEnum( - GLOverlay_Mode_descriptor(), name, value); -} -enum GLOverlay_Identifier { - GLOverlay_Identifier_END = 14, - GLOverlay_Identifier_VERTEX2F = 15, - GLOverlay_Identifier_VERTEX3F = 16, - GLOverlay_Identifier_ROTATEF = 17, - GLOverlay_Identifier_TRANSLATEF = 18, - GLOverlay_Identifier_SCALEF = 19, - GLOverlay_Identifier_PUSH_MATRIX = 20, - GLOverlay_Identifier_POP_MATRIX = 21, - GLOverlay_Identifier_COLOR3F = 22, - GLOverlay_Identifier_COLOR4F = 23, - GLOverlay_Identifier_POINTSIZE = 24, - GLOverlay_Identifier_LINEWIDTH = 25 -}; -bool GLOverlay_Identifier_IsValid(int value); -const GLOverlay_Identifier GLOverlay_Identifier_Identifier_MIN = GLOverlay_Identifier_END; -const GLOverlay_Identifier GLOverlay_Identifier_Identifier_MAX = GLOverlay_Identifier_LINEWIDTH; -const int GLOverlay_Identifier_Identifier_ARRAYSIZE = GLOverlay_Identifier_Identifier_MAX + 1; - -const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor(); -inline const ::std::string& GLOverlay_Identifier_Name(GLOverlay_Identifier value) { - return ::google::protobuf::internal::NameOfEnum( - GLOverlay_Identifier_descriptor(), value); -} -inline bool GLOverlay_Identifier_Parse( - const ::std::string& name, GLOverlay_Identifier* value) { - return ::google::protobuf::internal::ParseNamedEnum( - GLOverlay_Identifier_descriptor(), name, value); -} -// =================================================================== - -class HeaderInfo : public ::google::protobuf::Message { - public: - HeaderInfo(); - virtual ~HeaderInfo(); - - HeaderInfo(const HeaderInfo& from); - - inline HeaderInfo& operator=(const HeaderInfo& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const HeaderInfo& default_instance(); - - void Swap(HeaderInfo* other); - - // implements Message ---------------------------------------------- - - HeaderInfo* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const HeaderInfo& from); - void MergeFrom(const HeaderInfo& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required int32 source_sysid = 1; - inline bool has_source_sysid() const; - inline void clear_source_sysid(); - static const int kSourceSysidFieldNumber = 1; - inline ::google::protobuf::int32 source_sysid() const; - inline void set_source_sysid(::google::protobuf::int32 value); - - // required int32 source_compid = 2; - inline bool has_source_compid() const; - inline void clear_source_compid(); - static const int kSourceCompidFieldNumber = 2; - inline ::google::protobuf::int32 source_compid() const; - inline void set_source_compid(::google::protobuf::int32 value); - - // required double timestamp = 3; - inline bool has_timestamp() const; - inline void clear_timestamp(); - static const int kTimestampFieldNumber = 3; - inline double timestamp() const; - inline void set_timestamp(double value); - - // @@protoc_insertion_point(class_scope:px.HeaderInfo) - private: - inline void set_has_source_sysid(); - inline void clear_has_source_sysid(); - inline void set_has_source_compid(); - inline void clear_has_source_compid(); - inline void set_has_timestamp(); - inline void clear_has_timestamp(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::google::protobuf::int32 source_sysid_; - ::google::protobuf::int32 source_compid_; - double timestamp_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(3 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static HeaderInfo* default_instance_; -}; -// ------------------------------------------------------------------- - -class GLOverlay : public ::google::protobuf::Message { - public: - GLOverlay(); - virtual ~GLOverlay(); - - GLOverlay(const GLOverlay& from); - - inline GLOverlay& operator=(const GLOverlay& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const GLOverlay& default_instance(); - - void Swap(GLOverlay* other); - - // implements Message ---------------------------------------------- - - GLOverlay* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const GLOverlay& from); - void MergeFrom(const GLOverlay& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - typedef GLOverlay_CoordinateFrameType CoordinateFrameType; - static const CoordinateFrameType GLOBAL = GLOverlay_CoordinateFrameType_GLOBAL; - static const CoordinateFrameType LOCAL = GLOverlay_CoordinateFrameType_LOCAL; - static inline bool CoordinateFrameType_IsValid(int value) { - return GLOverlay_CoordinateFrameType_IsValid(value); - } - static const CoordinateFrameType CoordinateFrameType_MIN = - GLOverlay_CoordinateFrameType_CoordinateFrameType_MIN; - static const CoordinateFrameType CoordinateFrameType_MAX = - GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX; - static const int CoordinateFrameType_ARRAYSIZE = - GLOverlay_CoordinateFrameType_CoordinateFrameType_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* - CoordinateFrameType_descriptor() { - return GLOverlay_CoordinateFrameType_descriptor(); - } - static inline const ::std::string& CoordinateFrameType_Name(CoordinateFrameType value) { - return GLOverlay_CoordinateFrameType_Name(value); - } - static inline bool CoordinateFrameType_Parse(const ::std::string& name, - CoordinateFrameType* value) { - return GLOverlay_CoordinateFrameType_Parse(name, value); - } - - typedef GLOverlay_Mode Mode; - static const Mode POINTS = GLOverlay_Mode_POINTS; - static const Mode LINES = GLOverlay_Mode_LINES; - static const Mode LINE_STRIP = GLOverlay_Mode_LINE_STRIP; - static const Mode LINE_LOOP = GLOverlay_Mode_LINE_LOOP; - static const Mode TRIANGLES = GLOverlay_Mode_TRIANGLES; - static const Mode TRIANGLE_STRIP = GLOverlay_Mode_TRIANGLE_STRIP; - static const Mode TRIANGLE_FAN = GLOverlay_Mode_TRIANGLE_FAN; - static const Mode QUADS = GLOverlay_Mode_QUADS; - static const Mode QUAD_STRIP = GLOverlay_Mode_QUAD_STRIP; - static const Mode POLYGON = GLOverlay_Mode_POLYGON; - static const Mode SOLID_CIRCLE = GLOverlay_Mode_SOLID_CIRCLE; - static const Mode WIRE_CIRCLE = GLOverlay_Mode_WIRE_CIRCLE; - static const Mode SOLID_CUBE = GLOverlay_Mode_SOLID_CUBE; - static const Mode WIRE_CUBE = GLOverlay_Mode_WIRE_CUBE; - static inline bool Mode_IsValid(int value) { - return GLOverlay_Mode_IsValid(value); - } - static const Mode Mode_MIN = - GLOverlay_Mode_Mode_MIN; - static const Mode Mode_MAX = - GLOverlay_Mode_Mode_MAX; - static const int Mode_ARRAYSIZE = - GLOverlay_Mode_Mode_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* - Mode_descriptor() { - return GLOverlay_Mode_descriptor(); - } - static inline const ::std::string& Mode_Name(Mode value) { - return GLOverlay_Mode_Name(value); - } - static inline bool Mode_Parse(const ::std::string& name, - Mode* value) { - return GLOverlay_Mode_Parse(name, value); - } - - typedef GLOverlay_Identifier Identifier; - static const Identifier END = GLOverlay_Identifier_END; - static const Identifier VERTEX2F = GLOverlay_Identifier_VERTEX2F; - static const Identifier VERTEX3F = GLOverlay_Identifier_VERTEX3F; - static const Identifier ROTATEF = GLOverlay_Identifier_ROTATEF; - static const Identifier TRANSLATEF = GLOverlay_Identifier_TRANSLATEF; - static const Identifier SCALEF = GLOverlay_Identifier_SCALEF; - static const Identifier PUSH_MATRIX = GLOverlay_Identifier_PUSH_MATRIX; - static const Identifier POP_MATRIX = GLOverlay_Identifier_POP_MATRIX; - static const Identifier COLOR3F = GLOverlay_Identifier_COLOR3F; - static const Identifier COLOR4F = GLOverlay_Identifier_COLOR4F; - static const Identifier POINTSIZE = GLOverlay_Identifier_POINTSIZE; - static const Identifier LINEWIDTH = GLOverlay_Identifier_LINEWIDTH; - static inline bool Identifier_IsValid(int value) { - return GLOverlay_Identifier_IsValid(value); - } - static const Identifier Identifier_MIN = - GLOverlay_Identifier_Identifier_MIN; - static const Identifier Identifier_MAX = - GLOverlay_Identifier_Identifier_MAX; - static const int Identifier_ARRAYSIZE = - GLOverlay_Identifier_Identifier_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* - Identifier_descriptor() { - return GLOverlay_Identifier_descriptor(); - } - static inline const ::std::string& Identifier_Name(Identifier value) { - return GLOverlay_Identifier_Name(value); - } - static inline bool Identifier_Parse(const ::std::string& name, - Identifier* value) { - return GLOverlay_Identifier_Parse(name, value); - } - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // optional string name = 2; - inline bool has_name() const; - inline void clear_name(); - static const int kNameFieldNumber = 2; - inline const ::std::string& name() const; - inline void set_name(const ::std::string& value); - inline void set_name(const char* value); - inline void set_name(const char* value, size_t size); - inline ::std::string* mutable_name(); - inline ::std::string* release_name(); - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - inline bool has_coordinateframetype() const; - inline void clear_coordinateframetype(); - static const int kCoordinateFrameTypeFieldNumber = 3; - inline ::px::GLOverlay_CoordinateFrameType coordinateframetype() const; - inline void set_coordinateframetype(::px::GLOverlay_CoordinateFrameType value); - - // optional double origin_x = 4; - inline bool has_origin_x() const; - inline void clear_origin_x(); - static const int kOriginXFieldNumber = 4; - inline double origin_x() const; - inline void set_origin_x(double value); - - // optional double origin_y = 5; - inline bool has_origin_y() const; - inline void clear_origin_y(); - static const int kOriginYFieldNumber = 5; - inline double origin_y() const; - inline void set_origin_y(double value); - - // optional double origin_z = 6; - inline bool has_origin_z() const; - inline void clear_origin_z(); - static const int kOriginZFieldNumber = 6; - inline double origin_z() const; - inline void set_origin_z(double value); - - // optional bytes data = 7; - inline bool has_data() const; - inline void clear_data(); - static const int kDataFieldNumber = 7; - inline const ::std::string& data() const; - inline void set_data(const ::std::string& value); - inline void set_data(const char* value); - inline void set_data(const void* value, size_t size); - inline ::std::string* mutable_data(); - inline ::std::string* release_data(); - - // @@protoc_insertion_point(class_scope:px.GLOverlay) - private: - inline void set_has_header(); - inline void clear_has_header(); - inline void set_has_name(); - inline void clear_has_name(); - inline void set_has_coordinateframetype(); - inline void clear_has_coordinateframetype(); - inline void set_has_origin_x(); - inline void clear_has_origin_x(); - inline void set_has_origin_y(); - inline void clear_has_origin_y(); - inline void set_has_origin_z(); - inline void clear_has_origin_z(); - inline void set_has_data(); - inline void clear_has_data(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::std::string* name_; - double origin_x_; - double origin_y_; - double origin_z_; - ::std::string* data_; - int coordinateframetype_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(7 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static GLOverlay* default_instance_; -}; -// ------------------------------------------------------------------- - -class Obstacle : public ::google::protobuf::Message { - public: - Obstacle(); - virtual ~Obstacle(); - - Obstacle(const Obstacle& from); - - inline Obstacle& operator=(const Obstacle& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const Obstacle& default_instance(); - - void Swap(Obstacle* other); - - // implements Message ---------------------------------------------- - - Obstacle* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const Obstacle& from); - void MergeFrom(const Obstacle& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // optional float x = 1; - inline bool has_x() const; - inline void clear_x(); - static const int kXFieldNumber = 1; - inline float x() const; - inline void set_x(float value); - - // optional float y = 2; - inline bool has_y() const; - inline void clear_y(); - static const int kYFieldNumber = 2; - inline float y() const; - inline void set_y(float value); - - // optional float z = 3; - inline bool has_z() const; - inline void clear_z(); - static const int kZFieldNumber = 3; - inline float z() const; - inline void set_z(float value); - - // optional float length = 4; - inline bool has_length() const; - inline void clear_length(); - static const int kLengthFieldNumber = 4; - inline float length() const; - inline void set_length(float value); - - // optional float width = 5; - inline bool has_width() const; - inline void clear_width(); - static const int kWidthFieldNumber = 5; - inline float width() const; - inline void set_width(float value); - - // optional float height = 6; - inline bool has_height() const; - inline void clear_height(); - static const int kHeightFieldNumber = 6; - inline float height() const; - inline void set_height(float value); - - // @@protoc_insertion_point(class_scope:px.Obstacle) - private: - inline void set_has_x(); - inline void clear_has_x(); - inline void set_has_y(); - inline void clear_has_y(); - inline void set_has_z(); - inline void clear_has_z(); - inline void set_has_length(); - inline void clear_has_length(); - inline void set_has_width(); - inline void clear_has_width(); - inline void set_has_height(); - inline void clear_has_height(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - float x_; - float y_; - float z_; - float length_; - float width_; - float height_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(6 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static Obstacle* default_instance_; -}; -// ------------------------------------------------------------------- - -class ObstacleList : public ::google::protobuf::Message { - public: - ObstacleList(); - virtual ~ObstacleList(); - - ObstacleList(const ObstacleList& from); - - inline ObstacleList& operator=(const ObstacleList& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const ObstacleList& default_instance(); - - void Swap(ObstacleList* other); - - // implements Message ---------------------------------------------- - - ObstacleList* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const ObstacleList& from); - void MergeFrom(const ObstacleList& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // repeated .px.Obstacle obstacles = 2; - inline int obstacles_size() const; - inline void clear_obstacles(); - static const int kObstaclesFieldNumber = 2; - inline const ::px::Obstacle& obstacles(int index) const; - inline ::px::Obstacle* mutable_obstacles(int index); - inline ::px::Obstacle* add_obstacles(); - inline const ::google::protobuf::RepeatedPtrField< ::px::Obstacle >& - obstacles() const; - inline ::google::protobuf::RepeatedPtrField< ::px::Obstacle >* - mutable_obstacles(); - - // @@protoc_insertion_point(class_scope:px.ObstacleList) - private: - inline void set_has_header(); - inline void clear_has_header(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::RepeatedPtrField< ::px::Obstacle > obstacles_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static ObstacleList* default_instance_; -}; -// ------------------------------------------------------------------- - -class ObstacleMap : public ::google::protobuf::Message { - public: - ObstacleMap(); - virtual ~ObstacleMap(); - - ObstacleMap(const ObstacleMap& from); - - inline ObstacleMap& operator=(const ObstacleMap& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const ObstacleMap& default_instance(); - - void Swap(ObstacleMap* other); - - // implements Message ---------------------------------------------- - - ObstacleMap* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const ObstacleMap& from); - void MergeFrom(const ObstacleMap& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // required int32 type = 2; - inline bool has_type() const; - inline void clear_type(); - static const int kTypeFieldNumber = 2; - inline ::google::protobuf::int32 type() const; - inline void set_type(::google::protobuf::int32 value); - - // optional float resolution = 3; - inline bool has_resolution() const; - inline void clear_resolution(); - static const int kResolutionFieldNumber = 3; - inline float resolution() const; - inline void set_resolution(float value); - - // optional int32 rows = 4; - inline bool has_rows() const; - inline void clear_rows(); - static const int kRowsFieldNumber = 4; - inline ::google::protobuf::int32 rows() const; - inline void set_rows(::google::protobuf::int32 value); - - // optional int32 cols = 5; - inline bool has_cols() const; - inline void clear_cols(); - static const int kColsFieldNumber = 5; - inline ::google::protobuf::int32 cols() const; - inline void set_cols(::google::protobuf::int32 value); - - // optional int32 mapR0 = 6; - inline bool has_mapr0() const; - inline void clear_mapr0(); - static const int kMapR0FieldNumber = 6; - inline ::google::protobuf::int32 mapr0() const; - inline void set_mapr0(::google::protobuf::int32 value); - - // optional int32 mapC0 = 7; - inline bool has_mapc0() const; - inline void clear_mapc0(); - static const int kMapC0FieldNumber = 7; - inline ::google::protobuf::int32 mapc0() const; - inline void set_mapc0(::google::protobuf::int32 value); - - // optional int32 arrayR0 = 8; - inline bool has_arrayr0() const; - inline void clear_arrayr0(); - static const int kArrayR0FieldNumber = 8; - inline ::google::protobuf::int32 arrayr0() const; - inline void set_arrayr0(::google::protobuf::int32 value); - - // optional int32 arrayC0 = 9; - inline bool has_arrayc0() const; - inline void clear_arrayc0(); - static const int kArrayC0FieldNumber = 9; - inline ::google::protobuf::int32 arrayc0() const; - inline void set_arrayc0(::google::protobuf::int32 value); - - // optional bytes data = 10; - inline bool has_data() const; - inline void clear_data(); - static const int kDataFieldNumber = 10; - inline const ::std::string& data() const; - inline void set_data(const ::std::string& value); - inline void set_data(const char* value); - inline void set_data(const void* value, size_t size); - inline ::std::string* mutable_data(); - inline ::std::string* release_data(); - - // @@protoc_insertion_point(class_scope:px.ObstacleMap) - private: - inline void set_has_header(); - inline void clear_has_header(); - inline void set_has_type(); - inline void clear_has_type(); - inline void set_has_resolution(); - inline void clear_has_resolution(); - inline void set_has_rows(); - inline void clear_has_rows(); - inline void set_has_cols(); - inline void clear_has_cols(); - inline void set_has_mapr0(); - inline void clear_has_mapr0(); - inline void set_has_mapc0(); - inline void clear_has_mapc0(); - inline void set_has_arrayr0(); - inline void clear_has_arrayr0(); - inline void set_has_arrayc0(); - inline void clear_has_arrayc0(); - inline void set_has_data(); - inline void clear_has_data(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::int32 type_; - float resolution_; - ::google::protobuf::int32 rows_; - ::google::protobuf::int32 cols_; - ::google::protobuf::int32 mapr0_; - ::google::protobuf::int32 mapc0_; - ::google::protobuf::int32 arrayr0_; - ::google::protobuf::int32 arrayc0_; - ::std::string* data_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(10 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static ObstacleMap* default_instance_; -}; -// ------------------------------------------------------------------- - -class Path : public ::google::protobuf::Message { - public: - Path(); - virtual ~Path(); - - Path(const Path& from); - - inline Path& operator=(const Path& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const Path& default_instance(); - - void Swap(Path* other); - - // implements Message ---------------------------------------------- - - Path* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const Path& from); - void MergeFrom(const Path& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // repeated .px.Waypoint waypoints = 2; - inline int waypoints_size() const; - inline void clear_waypoints(); - static const int kWaypointsFieldNumber = 2; - inline const ::px::Waypoint& waypoints(int index) const; - inline ::px::Waypoint* mutable_waypoints(int index); - inline ::px::Waypoint* add_waypoints(); - inline const ::google::protobuf::RepeatedPtrField< ::px::Waypoint >& - waypoints() const; - inline ::google::protobuf::RepeatedPtrField< ::px::Waypoint >* - mutable_waypoints(); - - // @@protoc_insertion_point(class_scope:px.Path) - private: - inline void set_has_header(); - inline void clear_has_header(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::RepeatedPtrField< ::px::Waypoint > waypoints_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static Path* default_instance_; -}; -// ------------------------------------------------------------------- - -class PointCloudXYZI_PointXYZI : public ::google::protobuf::Message { - public: - PointCloudXYZI_PointXYZI(); - virtual ~PointCloudXYZI_PointXYZI(); - - PointCloudXYZI_PointXYZI(const PointCloudXYZI_PointXYZI& from); - - inline PointCloudXYZI_PointXYZI& operator=(const PointCloudXYZI_PointXYZI& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const PointCloudXYZI_PointXYZI& default_instance(); - - void Swap(PointCloudXYZI_PointXYZI* other); - - // implements Message ---------------------------------------------- - - PointCloudXYZI_PointXYZI* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const PointCloudXYZI_PointXYZI& from); - void MergeFrom(const PointCloudXYZI_PointXYZI& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required float x = 1; - inline bool has_x() const; - inline void clear_x(); - static const int kXFieldNumber = 1; - inline float x() const; - inline void set_x(float value); - - // required float y = 2; - inline bool has_y() const; - inline void clear_y(); - static const int kYFieldNumber = 2; - inline float y() const; - inline void set_y(float value); - - // required float z = 3; - inline bool has_z() const; - inline void clear_z(); - static const int kZFieldNumber = 3; - inline float z() const; - inline void set_z(float value); - - // required float intensity = 4; - inline bool has_intensity() const; - inline void clear_intensity(); - static const int kIntensityFieldNumber = 4; - inline float intensity() const; - inline void set_intensity(float value); - - // @@protoc_insertion_point(class_scope:px.PointCloudXYZI.PointXYZI) - private: - inline void set_has_x(); - inline void clear_has_x(); - inline void set_has_y(); - inline void clear_has_y(); - inline void set_has_z(); - inline void clear_has_z(); - inline void set_has_intensity(); - inline void clear_has_intensity(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - float x_; - float y_; - float z_; - float intensity_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(4 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static PointCloudXYZI_PointXYZI* default_instance_; -}; -// ------------------------------------------------------------------- - -class PointCloudXYZI : public ::google::protobuf::Message { - public: - PointCloudXYZI(); - virtual ~PointCloudXYZI(); - - PointCloudXYZI(const PointCloudXYZI& from); - - inline PointCloudXYZI& operator=(const PointCloudXYZI& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const PointCloudXYZI& default_instance(); - - void Swap(PointCloudXYZI* other); - - // implements Message ---------------------------------------------- - - PointCloudXYZI* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const PointCloudXYZI& from); - void MergeFrom(const PointCloudXYZI& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - typedef PointCloudXYZI_PointXYZI PointXYZI; - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - inline int points_size() const; - inline void clear_points(); - static const int kPointsFieldNumber = 2; - inline const ::px::PointCloudXYZI_PointXYZI& points(int index) const; - inline ::px::PointCloudXYZI_PointXYZI* mutable_points(int index); - inline ::px::PointCloudXYZI_PointXYZI* add_points(); - inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >& - points() const; - inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >* - mutable_points(); - - // @@protoc_insertion_point(class_scope:px.PointCloudXYZI) - private: - inline void set_has_header(); - inline void clear_has_header(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI > points_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static PointCloudXYZI* default_instance_; -}; -// ------------------------------------------------------------------- - -class PointCloudXYZRGB_PointXYZRGB : public ::google::protobuf::Message { - public: - PointCloudXYZRGB_PointXYZRGB(); - virtual ~PointCloudXYZRGB_PointXYZRGB(); - - PointCloudXYZRGB_PointXYZRGB(const PointCloudXYZRGB_PointXYZRGB& from); - - inline PointCloudXYZRGB_PointXYZRGB& operator=(const PointCloudXYZRGB_PointXYZRGB& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const PointCloudXYZRGB_PointXYZRGB& default_instance(); - - void Swap(PointCloudXYZRGB_PointXYZRGB* other); - - // implements Message ---------------------------------------------- - - PointCloudXYZRGB_PointXYZRGB* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const PointCloudXYZRGB_PointXYZRGB& from); - void MergeFrom(const PointCloudXYZRGB_PointXYZRGB& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required float x = 1; - inline bool has_x() const; - inline void clear_x(); - static const int kXFieldNumber = 1; - inline float x() const; - inline void set_x(float value); - - // required float y = 2; - inline bool has_y() const; - inline void clear_y(); - static const int kYFieldNumber = 2; - inline float y() const; - inline void set_y(float value); - - // required float z = 3; - inline bool has_z() const; - inline void clear_z(); - static const int kZFieldNumber = 3; - inline float z() const; - inline void set_z(float value); - - // required float rgb = 4; - inline bool has_rgb() const; - inline void clear_rgb(); - static const int kRgbFieldNumber = 4; - inline float rgb() const; - inline void set_rgb(float value); - - // @@protoc_insertion_point(class_scope:px.PointCloudXYZRGB.PointXYZRGB) - private: - inline void set_has_x(); - inline void clear_has_x(); - inline void set_has_y(); - inline void clear_has_y(); - inline void set_has_z(); - inline void clear_has_z(); - inline void set_has_rgb(); - inline void clear_has_rgb(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - float x_; - float y_; - float z_; - float rgb_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(4 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static PointCloudXYZRGB_PointXYZRGB* default_instance_; -}; -// ------------------------------------------------------------------- - -class PointCloudXYZRGB : public ::google::protobuf::Message { - public: - PointCloudXYZRGB(); - virtual ~PointCloudXYZRGB(); - - PointCloudXYZRGB(const PointCloudXYZRGB& from); - - inline PointCloudXYZRGB& operator=(const PointCloudXYZRGB& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const PointCloudXYZRGB& default_instance(); - - void Swap(PointCloudXYZRGB* other); - - // implements Message ---------------------------------------------- - - PointCloudXYZRGB* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const PointCloudXYZRGB& from); - void MergeFrom(const PointCloudXYZRGB& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - typedef PointCloudXYZRGB_PointXYZRGB PointXYZRGB; - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - inline int points_size() const; - inline void clear_points(); - static const int kPointsFieldNumber = 2; - inline const ::px::PointCloudXYZRGB_PointXYZRGB& points(int index) const; - inline ::px::PointCloudXYZRGB_PointXYZRGB* mutable_points(int index); - inline ::px::PointCloudXYZRGB_PointXYZRGB* add_points(); - inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >& - points() const; - inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >* - mutable_points(); - - // @@protoc_insertion_point(class_scope:px.PointCloudXYZRGB) - private: - inline void set_has_header(); - inline void clear_has_header(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB > points_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static PointCloudXYZRGB* default_instance_; -}; -// ------------------------------------------------------------------- - -class RGBDImage : public ::google::protobuf::Message { - public: - RGBDImage(); - virtual ~RGBDImage(); - - RGBDImage(const RGBDImage& from); - - inline RGBDImage& operator=(const RGBDImage& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const RGBDImage& default_instance(); - - void Swap(RGBDImage* other); - - // implements Message ---------------------------------------------- - - RGBDImage* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const RGBDImage& from); - void MergeFrom(const RGBDImage& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // required uint32 cols = 2; - inline bool has_cols() const; - inline void clear_cols(); - static const int kColsFieldNumber = 2; - inline ::google::protobuf::uint32 cols() const; - inline void set_cols(::google::protobuf::uint32 value); - - // required uint32 rows = 3; - inline bool has_rows() const; - inline void clear_rows(); - static const int kRowsFieldNumber = 3; - inline ::google::protobuf::uint32 rows() const; - inline void set_rows(::google::protobuf::uint32 value); - - // required uint32 step1 = 4; - inline bool has_step1() const; - inline void clear_step1(); - static const int kStep1FieldNumber = 4; - inline ::google::protobuf::uint32 step1() const; - inline void set_step1(::google::protobuf::uint32 value); - - // required uint32 type1 = 5; - inline bool has_type1() const; - inline void clear_type1(); - static const int kType1FieldNumber = 5; - inline ::google::protobuf::uint32 type1() const; - inline void set_type1(::google::protobuf::uint32 value); - - // required bytes imageData1 = 6; - inline bool has_imagedata1() const; - inline void clear_imagedata1(); - static const int kImageData1FieldNumber = 6; - inline const ::std::string& imagedata1() const; - inline void set_imagedata1(const ::std::string& value); - inline void set_imagedata1(const char* value); - inline void set_imagedata1(const void* value, size_t size); - inline ::std::string* mutable_imagedata1(); - inline ::std::string* release_imagedata1(); - - // required uint32 step2 = 7; - inline bool has_step2() const; - inline void clear_step2(); - static const int kStep2FieldNumber = 7; - inline ::google::protobuf::uint32 step2() const; - inline void set_step2(::google::protobuf::uint32 value); - - // required uint32 type2 = 8; - inline bool has_type2() const; - inline void clear_type2(); - static const int kType2FieldNumber = 8; - inline ::google::protobuf::uint32 type2() const; - inline void set_type2(::google::protobuf::uint32 value); - - // required bytes imageData2 = 9; - inline bool has_imagedata2() const; - inline void clear_imagedata2(); - static const int kImageData2FieldNumber = 9; - inline const ::std::string& imagedata2() const; - inline void set_imagedata2(const ::std::string& value); - inline void set_imagedata2(const char* value); - inline void set_imagedata2(const void* value, size_t size); - inline ::std::string* mutable_imagedata2(); - inline ::std::string* release_imagedata2(); - - // optional uint32 camera_config = 10; - inline bool has_camera_config() const; - inline void clear_camera_config(); - static const int kCameraConfigFieldNumber = 10; - inline ::google::protobuf::uint32 camera_config() const; - inline void set_camera_config(::google::protobuf::uint32 value); - - // optional uint32 camera_type = 11; - inline bool has_camera_type() const; - inline void clear_camera_type(); - static const int kCameraTypeFieldNumber = 11; - inline ::google::protobuf::uint32 camera_type() const; - inline void set_camera_type(::google::protobuf::uint32 value); - - // optional float roll = 12; - inline bool has_roll() const; - inline void clear_roll(); - static const int kRollFieldNumber = 12; - inline float roll() const; - inline void set_roll(float value); - - // optional float pitch = 13; - inline bool has_pitch() const; - inline void clear_pitch(); - static const int kPitchFieldNumber = 13; - inline float pitch() const; - inline void set_pitch(float value); - - // optional float yaw = 14; - inline bool has_yaw() const; - inline void clear_yaw(); - static const int kYawFieldNumber = 14; - inline float yaw() const; - inline void set_yaw(float value); - - // optional float lon = 15; - inline bool has_lon() const; - inline void clear_lon(); - static const int kLonFieldNumber = 15; - inline float lon() const; - inline void set_lon(float value); - - // optional float lat = 16; - inline bool has_lat() const; - inline void clear_lat(); - static const int kLatFieldNumber = 16; - inline float lat() const; - inline void set_lat(float value); - - // optional float alt = 17; - inline bool has_alt() const; - inline void clear_alt(); - static const int kAltFieldNumber = 17; - inline float alt() const; - inline void set_alt(float value); - - // optional float ground_x = 18; - inline bool has_ground_x() const; - inline void clear_ground_x(); - static const int kGroundXFieldNumber = 18; - inline float ground_x() const; - inline void set_ground_x(float value); - - // optional float ground_y = 19; - inline bool has_ground_y() const; - inline void clear_ground_y(); - static const int kGroundYFieldNumber = 19; - inline float ground_y() const; - inline void set_ground_y(float value); - - // optional float ground_z = 20; - inline bool has_ground_z() const; - inline void clear_ground_z(); - static const int kGroundZFieldNumber = 20; - inline float ground_z() const; - inline void set_ground_z(float value); - - // repeated float camera_matrix = 21; - inline int camera_matrix_size() const; - inline void clear_camera_matrix(); - static const int kCameraMatrixFieldNumber = 21; - inline float camera_matrix(int index) const; - inline void set_camera_matrix(int index, float value); - inline void add_camera_matrix(float value); - inline const ::google::protobuf::RepeatedField< float >& - camera_matrix() const; - inline ::google::protobuf::RepeatedField< float >* - mutable_camera_matrix(); - - // @@protoc_insertion_point(class_scope:px.RGBDImage) - private: - inline void set_has_header(); - inline void clear_has_header(); - inline void set_has_cols(); - inline void clear_has_cols(); - inline void set_has_rows(); - inline void clear_has_rows(); - inline void set_has_step1(); - inline void clear_has_step1(); - inline void set_has_type1(); - inline void clear_has_type1(); - inline void set_has_imagedata1(); - inline void clear_has_imagedata1(); - inline void set_has_step2(); - inline void clear_has_step2(); - inline void set_has_type2(); - inline void clear_has_type2(); - inline void set_has_imagedata2(); - inline void clear_has_imagedata2(); - inline void set_has_camera_config(); - inline void clear_has_camera_config(); - inline void set_has_camera_type(); - inline void clear_has_camera_type(); - inline void set_has_roll(); - inline void clear_has_roll(); - inline void set_has_pitch(); - inline void clear_has_pitch(); - inline void set_has_yaw(); - inline void clear_has_yaw(); - inline void set_has_lon(); - inline void clear_has_lon(); - inline void set_has_lat(); - inline void clear_has_lat(); - inline void set_has_alt(); - inline void clear_has_alt(); - inline void set_has_ground_x(); - inline void clear_has_ground_x(); - inline void set_has_ground_y(); - inline void clear_has_ground_y(); - inline void set_has_ground_z(); - inline void clear_has_ground_z(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::uint32 cols_; - ::google::protobuf::uint32 rows_; - ::google::protobuf::uint32 step1_; - ::google::protobuf::uint32 type1_; - ::std::string* imagedata1_; - ::google::protobuf::uint32 step2_; - ::google::protobuf::uint32 type2_; - ::std::string* imagedata2_; - ::google::protobuf::uint32 camera_config_; - ::google::protobuf::uint32 camera_type_; - float roll_; - float pitch_; - float yaw_; - float lon_; - float lat_; - float alt_; - float ground_x_; - float ground_y_; - ::google::protobuf::RepeatedField< float > camera_matrix_; - float ground_z_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(21 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static RGBDImage* default_instance_; -}; -// ------------------------------------------------------------------- - -class Waypoint : public ::google::protobuf::Message { - public: - Waypoint(); - virtual ~Waypoint(); - - Waypoint(const Waypoint& from); - - inline Waypoint& operator=(const Waypoint& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const Waypoint& default_instance(); - - void Swap(Waypoint* other); - - // implements Message ---------------------------------------------- - - Waypoint* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const Waypoint& from); - void MergeFrom(const Waypoint& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required double x = 1; - inline bool has_x() const; - inline void clear_x(); - static const int kXFieldNumber = 1; - inline double x() const; - inline void set_x(double value); - - // required double y = 2; - inline bool has_y() const; - inline void clear_y(); - static const int kYFieldNumber = 2; - inline double y() const; - inline void set_y(double value); - - // optional double z = 3; - inline bool has_z() const; - inline void clear_z(); - static const int kZFieldNumber = 3; - inline double z() const; - inline void set_z(double value); - - // optional double roll = 4; - inline bool has_roll() const; - inline void clear_roll(); - static const int kRollFieldNumber = 4; - inline double roll() const; - inline void set_roll(double value); - - // optional double pitch = 5; - inline bool has_pitch() const; - inline void clear_pitch(); - static const int kPitchFieldNumber = 5; - inline double pitch() const; - inline void set_pitch(double value); - - // optional double yaw = 6; - inline bool has_yaw() const; - inline void clear_yaw(); - static const int kYawFieldNumber = 6; - inline double yaw() const; - inline void set_yaw(double value); - - // @@protoc_insertion_point(class_scope:px.Waypoint) - private: - inline void set_has_x(); - inline void clear_has_x(); - inline void set_has_y(); - inline void clear_has_y(); - inline void set_has_z(); - inline void clear_has_z(); - inline void set_has_roll(); - inline void clear_has_roll(); - inline void set_has_pitch(); - inline void clear_has_pitch(); - inline void set_has_yaw(); - inline void clear_has_yaw(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - double x_; - double y_; - double z_; - double roll_; - double pitch_; - double yaw_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(6 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static Waypoint* default_instance_; -}; -// =================================================================== - - -// =================================================================== - -// HeaderInfo - -// required int32 source_sysid = 1; -inline bool HeaderInfo::has_source_sysid() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void HeaderInfo::set_has_source_sysid() { - _has_bits_[0] |= 0x00000001u; -} -inline void HeaderInfo::clear_has_source_sysid() { - _has_bits_[0] &= ~0x00000001u; -} -inline void HeaderInfo::clear_source_sysid() { - source_sysid_ = 0; - clear_has_source_sysid(); -} -inline ::google::protobuf::int32 HeaderInfo::source_sysid() const { - return source_sysid_; -} -inline void HeaderInfo::set_source_sysid(::google::protobuf::int32 value) { - set_has_source_sysid(); - source_sysid_ = value; -} - -// required int32 source_compid = 2; -inline bool HeaderInfo::has_source_compid() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void HeaderInfo::set_has_source_compid() { - _has_bits_[0] |= 0x00000002u; -} -inline void HeaderInfo::clear_has_source_compid() { - _has_bits_[0] &= ~0x00000002u; -} -inline void HeaderInfo::clear_source_compid() { - source_compid_ = 0; - clear_has_source_compid(); -} -inline ::google::protobuf::int32 HeaderInfo::source_compid() const { - return source_compid_; -} -inline void HeaderInfo::set_source_compid(::google::protobuf::int32 value) { - set_has_source_compid(); - source_compid_ = value; -} - -// required double timestamp = 3; -inline bool HeaderInfo::has_timestamp() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void HeaderInfo::set_has_timestamp() { - _has_bits_[0] |= 0x00000004u; -} -inline void HeaderInfo::clear_has_timestamp() { - _has_bits_[0] &= ~0x00000004u; -} -inline void HeaderInfo::clear_timestamp() { - timestamp_ = 0; - clear_has_timestamp(); -} -inline double HeaderInfo::timestamp() const { - return timestamp_; -} -inline void HeaderInfo::set_timestamp(double value) { - set_has_timestamp(); - timestamp_ = value; -} - -// ------------------------------------------------------------------- - -// GLOverlay - -// required .px.HeaderInfo header = 1; -inline bool GLOverlay::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void GLOverlay::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void GLOverlay::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void GLOverlay::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& GLOverlay::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* GLOverlay::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* GLOverlay::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// optional string name = 2; -inline bool GLOverlay::has_name() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void GLOverlay::set_has_name() { - _has_bits_[0] |= 0x00000002u; -} -inline void GLOverlay::clear_has_name() { - _has_bits_[0] &= ~0x00000002u; -} -inline void GLOverlay::clear_name() { - if (name_ != &::google::protobuf::internal::kEmptyString) { - name_->clear(); - } - clear_has_name(); -} -inline const ::std::string& GLOverlay::name() const { - return *name_; -} -inline void GLOverlay::set_name(const ::std::string& value) { - set_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - name_ = new ::std::string; - } - name_->assign(value); -} -inline void GLOverlay::set_name(const char* value) { - set_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - name_ = new ::std::string; - } - name_->assign(value); -} -inline void GLOverlay::set_name(const char* value, size_t size) { - set_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - name_ = new ::std::string; - } - name_->assign(reinterpret_cast(value), size); -} -inline ::std::string* GLOverlay::mutable_name() { - set_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - name_ = new ::std::string; - } - return name_; -} -inline ::std::string* GLOverlay::release_name() { - clear_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = name_; - name_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; -inline bool GLOverlay::has_coordinateframetype() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void GLOverlay::set_has_coordinateframetype() { - _has_bits_[0] |= 0x00000004u; -} -inline void GLOverlay::clear_has_coordinateframetype() { - _has_bits_[0] &= ~0x00000004u; -} -inline void GLOverlay::clear_coordinateframetype() { - coordinateframetype_ = 0; - clear_has_coordinateframetype(); -} -inline ::px::GLOverlay_CoordinateFrameType GLOverlay::coordinateframetype() const { - return static_cast< ::px::GLOverlay_CoordinateFrameType >(coordinateframetype_); -} -inline void GLOverlay::set_coordinateframetype(::px::GLOverlay_CoordinateFrameType value) { - GOOGLE_DCHECK(::px::GLOverlay_CoordinateFrameType_IsValid(value)); - set_has_coordinateframetype(); - coordinateframetype_ = value; -} - -// optional double origin_x = 4; -inline bool GLOverlay::has_origin_x() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void GLOverlay::set_has_origin_x() { - _has_bits_[0] |= 0x00000008u; -} -inline void GLOverlay::clear_has_origin_x() { - _has_bits_[0] &= ~0x00000008u; -} -inline void GLOverlay::clear_origin_x() { - origin_x_ = 0; - clear_has_origin_x(); -} -inline double GLOverlay::origin_x() const { - return origin_x_; -} -inline void GLOverlay::set_origin_x(double value) { - set_has_origin_x(); - origin_x_ = value; -} - -// optional double origin_y = 5; -inline bool GLOverlay::has_origin_y() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void GLOverlay::set_has_origin_y() { - _has_bits_[0] |= 0x00000010u; -} -inline void GLOverlay::clear_has_origin_y() { - _has_bits_[0] &= ~0x00000010u; -} -inline void GLOverlay::clear_origin_y() { - origin_y_ = 0; - clear_has_origin_y(); -} -inline double GLOverlay::origin_y() const { - return origin_y_; -} -inline void GLOverlay::set_origin_y(double value) { - set_has_origin_y(); - origin_y_ = value; -} - -// optional double origin_z = 6; -inline bool GLOverlay::has_origin_z() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void GLOverlay::set_has_origin_z() { - _has_bits_[0] |= 0x00000020u; -} -inline void GLOverlay::clear_has_origin_z() { - _has_bits_[0] &= ~0x00000020u; -} -inline void GLOverlay::clear_origin_z() { - origin_z_ = 0; - clear_has_origin_z(); -} -inline double GLOverlay::origin_z() const { - return origin_z_; -} -inline void GLOverlay::set_origin_z(double value) { - set_has_origin_z(); - origin_z_ = value; -} - -// optional bytes data = 7; -inline bool GLOverlay::has_data() const { - return (_has_bits_[0] & 0x00000040u) != 0; -} -inline void GLOverlay::set_has_data() { - _has_bits_[0] |= 0x00000040u; -} -inline void GLOverlay::clear_has_data() { - _has_bits_[0] &= ~0x00000040u; -} -inline void GLOverlay::clear_data() { - if (data_ != &::google::protobuf::internal::kEmptyString) { - data_->clear(); - } - clear_has_data(); -} -inline const ::std::string& GLOverlay::data() const { - return *data_; -} -inline void GLOverlay::set_data(const ::std::string& value) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(value); -} -inline void GLOverlay::set_data(const char* value) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(value); -} -inline void GLOverlay::set_data(const void* value, size_t size) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(reinterpret_cast(value), size); -} -inline ::std::string* GLOverlay::mutable_data() { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - return data_; -} -inline ::std::string* GLOverlay::release_data() { - clear_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = data_; - data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// ------------------------------------------------------------------- - -// Obstacle - -// optional float x = 1; -inline bool Obstacle::has_x() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void Obstacle::set_has_x() { - _has_bits_[0] |= 0x00000001u; -} -inline void Obstacle::clear_has_x() { - _has_bits_[0] &= ~0x00000001u; -} -inline void Obstacle::clear_x() { - x_ = 0; - clear_has_x(); -} -inline float Obstacle::x() const { - return x_; -} -inline void Obstacle::set_x(float value) { - set_has_x(); - x_ = value; -} - -// optional float y = 2; -inline bool Obstacle::has_y() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void Obstacle::set_has_y() { - _has_bits_[0] |= 0x00000002u; -} -inline void Obstacle::clear_has_y() { - _has_bits_[0] &= ~0x00000002u; -} -inline void Obstacle::clear_y() { - y_ = 0; - clear_has_y(); -} -inline float Obstacle::y() const { - return y_; -} -inline void Obstacle::set_y(float value) { - set_has_y(); - y_ = value; -} - -// optional float z = 3; -inline bool Obstacle::has_z() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void Obstacle::set_has_z() { - _has_bits_[0] |= 0x00000004u; -} -inline void Obstacle::clear_has_z() { - _has_bits_[0] &= ~0x00000004u; -} -inline void Obstacle::clear_z() { - z_ = 0; - clear_has_z(); -} -inline float Obstacle::z() const { - return z_; -} -inline void Obstacle::set_z(float value) { - set_has_z(); - z_ = value; -} - -// optional float length = 4; -inline bool Obstacle::has_length() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void Obstacle::set_has_length() { - _has_bits_[0] |= 0x00000008u; -} -inline void Obstacle::clear_has_length() { - _has_bits_[0] &= ~0x00000008u; -} -inline void Obstacle::clear_length() { - length_ = 0; - clear_has_length(); -} -inline float Obstacle::length() const { - return length_; -} -inline void Obstacle::set_length(float value) { - set_has_length(); - length_ = value; -} - -// optional float width = 5; -inline bool Obstacle::has_width() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void Obstacle::set_has_width() { - _has_bits_[0] |= 0x00000010u; -} -inline void Obstacle::clear_has_width() { - _has_bits_[0] &= ~0x00000010u; -} -inline void Obstacle::clear_width() { - width_ = 0; - clear_has_width(); -} -inline float Obstacle::width() const { - return width_; -} -inline void Obstacle::set_width(float value) { - set_has_width(); - width_ = value; -} - -// optional float height = 6; -inline bool Obstacle::has_height() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void Obstacle::set_has_height() { - _has_bits_[0] |= 0x00000020u; -} -inline void Obstacle::clear_has_height() { - _has_bits_[0] &= ~0x00000020u; -} -inline void Obstacle::clear_height() { - height_ = 0; - clear_has_height(); -} -inline float Obstacle::height() const { - return height_; -} -inline void Obstacle::set_height(float value) { - set_has_height(); - height_ = value; -} - -// ------------------------------------------------------------------- - -// ObstacleList - -// required .px.HeaderInfo header = 1; -inline bool ObstacleList::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void ObstacleList::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void ObstacleList::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void ObstacleList::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& ObstacleList::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* ObstacleList::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* ObstacleList::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// repeated .px.Obstacle obstacles = 2; -inline int ObstacleList::obstacles_size() const { - return obstacles_.size(); -} -inline void ObstacleList::clear_obstacles() { - obstacles_.Clear(); -} -inline const ::px::Obstacle& ObstacleList::obstacles(int index) const { - return obstacles_.Get(index); -} -inline ::px::Obstacle* ObstacleList::mutable_obstacles(int index) { - return obstacles_.Mutable(index); -} -inline ::px::Obstacle* ObstacleList::add_obstacles() { - return obstacles_.Add(); -} -inline const ::google::protobuf::RepeatedPtrField< ::px::Obstacle >& -ObstacleList::obstacles() const { - return obstacles_; -} -inline ::google::protobuf::RepeatedPtrField< ::px::Obstacle >* -ObstacleList::mutable_obstacles() { - return &obstacles_; -} - -// ------------------------------------------------------------------- - -// ObstacleMap - -// required .px.HeaderInfo header = 1; -inline bool ObstacleMap::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void ObstacleMap::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void ObstacleMap::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void ObstacleMap::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& ObstacleMap::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* ObstacleMap::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* ObstacleMap::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// required int32 type = 2; -inline bool ObstacleMap::has_type() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void ObstacleMap::set_has_type() { - _has_bits_[0] |= 0x00000002u; -} -inline void ObstacleMap::clear_has_type() { - _has_bits_[0] &= ~0x00000002u; -} -inline void ObstacleMap::clear_type() { - type_ = 0; - clear_has_type(); -} -inline ::google::protobuf::int32 ObstacleMap::type() const { - return type_; -} -inline void ObstacleMap::set_type(::google::protobuf::int32 value) { - set_has_type(); - type_ = value; -} - -// optional float resolution = 3; -inline bool ObstacleMap::has_resolution() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void ObstacleMap::set_has_resolution() { - _has_bits_[0] |= 0x00000004u; -} -inline void ObstacleMap::clear_has_resolution() { - _has_bits_[0] &= ~0x00000004u; -} -inline void ObstacleMap::clear_resolution() { - resolution_ = 0; - clear_has_resolution(); -} -inline float ObstacleMap::resolution() const { - return resolution_; -} -inline void ObstacleMap::set_resolution(float value) { - set_has_resolution(); - resolution_ = value; -} - -// optional int32 rows = 4; -inline bool ObstacleMap::has_rows() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void ObstacleMap::set_has_rows() { - _has_bits_[0] |= 0x00000008u; -} -inline void ObstacleMap::clear_has_rows() { - _has_bits_[0] &= ~0x00000008u; -} -inline void ObstacleMap::clear_rows() { - rows_ = 0; - clear_has_rows(); -} -inline ::google::protobuf::int32 ObstacleMap::rows() const { - return rows_; -} -inline void ObstacleMap::set_rows(::google::protobuf::int32 value) { - set_has_rows(); - rows_ = value; -} - -// optional int32 cols = 5; -inline bool ObstacleMap::has_cols() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void ObstacleMap::set_has_cols() { - _has_bits_[0] |= 0x00000010u; -} -inline void ObstacleMap::clear_has_cols() { - _has_bits_[0] &= ~0x00000010u; -} -inline void ObstacleMap::clear_cols() { - cols_ = 0; - clear_has_cols(); -} -inline ::google::protobuf::int32 ObstacleMap::cols() const { - return cols_; -} -inline void ObstacleMap::set_cols(::google::protobuf::int32 value) { - set_has_cols(); - cols_ = value; -} - -// optional int32 mapR0 = 6; -inline bool ObstacleMap::has_mapr0() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void ObstacleMap::set_has_mapr0() { - _has_bits_[0] |= 0x00000020u; -} -inline void ObstacleMap::clear_has_mapr0() { - _has_bits_[0] &= ~0x00000020u; -} -inline void ObstacleMap::clear_mapr0() { - mapr0_ = 0; - clear_has_mapr0(); -} -inline ::google::protobuf::int32 ObstacleMap::mapr0() const { - return mapr0_; -} -inline void ObstacleMap::set_mapr0(::google::protobuf::int32 value) { - set_has_mapr0(); - mapr0_ = value; -} - -// optional int32 mapC0 = 7; -inline bool ObstacleMap::has_mapc0() const { - return (_has_bits_[0] & 0x00000040u) != 0; -} -inline void ObstacleMap::set_has_mapc0() { - _has_bits_[0] |= 0x00000040u; -} -inline void ObstacleMap::clear_has_mapc0() { - _has_bits_[0] &= ~0x00000040u; -} -inline void ObstacleMap::clear_mapc0() { - mapc0_ = 0; - clear_has_mapc0(); -} -inline ::google::protobuf::int32 ObstacleMap::mapc0() const { - return mapc0_; -} -inline void ObstacleMap::set_mapc0(::google::protobuf::int32 value) { - set_has_mapc0(); - mapc0_ = value; -} - -// optional int32 arrayR0 = 8; -inline bool ObstacleMap::has_arrayr0() const { - return (_has_bits_[0] & 0x00000080u) != 0; -} -inline void ObstacleMap::set_has_arrayr0() { - _has_bits_[0] |= 0x00000080u; -} -inline void ObstacleMap::clear_has_arrayr0() { - _has_bits_[0] &= ~0x00000080u; -} -inline void ObstacleMap::clear_arrayr0() { - arrayr0_ = 0; - clear_has_arrayr0(); -} -inline ::google::protobuf::int32 ObstacleMap::arrayr0() const { - return arrayr0_; -} -inline void ObstacleMap::set_arrayr0(::google::protobuf::int32 value) { - set_has_arrayr0(); - arrayr0_ = value; -} - -// optional int32 arrayC0 = 9; -inline bool ObstacleMap::has_arrayc0() const { - return (_has_bits_[0] & 0x00000100u) != 0; -} -inline void ObstacleMap::set_has_arrayc0() { - _has_bits_[0] |= 0x00000100u; -} -inline void ObstacleMap::clear_has_arrayc0() { - _has_bits_[0] &= ~0x00000100u; -} -inline void ObstacleMap::clear_arrayc0() { - arrayc0_ = 0; - clear_has_arrayc0(); -} -inline ::google::protobuf::int32 ObstacleMap::arrayc0() const { - return arrayc0_; -} -inline void ObstacleMap::set_arrayc0(::google::protobuf::int32 value) { - set_has_arrayc0(); - arrayc0_ = value; -} - -// optional bytes data = 10; -inline bool ObstacleMap::has_data() const { - return (_has_bits_[0] & 0x00000200u) != 0; -} -inline void ObstacleMap::set_has_data() { - _has_bits_[0] |= 0x00000200u; -} -inline void ObstacleMap::clear_has_data() { - _has_bits_[0] &= ~0x00000200u; -} -inline void ObstacleMap::clear_data() { - if (data_ != &::google::protobuf::internal::kEmptyString) { - data_->clear(); - } - clear_has_data(); -} -inline const ::std::string& ObstacleMap::data() const { - return *data_; -} -inline void ObstacleMap::set_data(const ::std::string& value) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(value); -} -inline void ObstacleMap::set_data(const char* value) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(value); -} -inline void ObstacleMap::set_data(const void* value, size_t size) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(reinterpret_cast(value), size); -} -inline ::std::string* ObstacleMap::mutable_data() { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - return data_; -} -inline ::std::string* ObstacleMap::release_data() { - clear_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = data_; - data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// ------------------------------------------------------------------- - -// Path - -// required .px.HeaderInfo header = 1; -inline bool Path::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void Path::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void Path::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void Path::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& Path::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* Path::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* Path::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// repeated .px.Waypoint waypoints = 2; -inline int Path::waypoints_size() const { - return waypoints_.size(); -} -inline void Path::clear_waypoints() { - waypoints_.Clear(); -} -inline const ::px::Waypoint& Path::waypoints(int index) const { - return waypoints_.Get(index); -} -inline ::px::Waypoint* Path::mutable_waypoints(int index) { - return waypoints_.Mutable(index); -} -inline ::px::Waypoint* Path::add_waypoints() { - return waypoints_.Add(); -} -inline const ::google::protobuf::RepeatedPtrField< ::px::Waypoint >& -Path::waypoints() const { - return waypoints_; -} -inline ::google::protobuf::RepeatedPtrField< ::px::Waypoint >* -Path::mutable_waypoints() { - return &waypoints_; -} - -// ------------------------------------------------------------------- - -// PointCloudXYZI_PointXYZI - -// required float x = 1; -inline bool PointCloudXYZI_PointXYZI::has_x() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void PointCloudXYZI_PointXYZI::set_has_x() { - _has_bits_[0] |= 0x00000001u; -} -inline void PointCloudXYZI_PointXYZI::clear_has_x() { - _has_bits_[0] &= ~0x00000001u; -} -inline void PointCloudXYZI_PointXYZI::clear_x() { - x_ = 0; - clear_has_x(); -} -inline float PointCloudXYZI_PointXYZI::x() const { - return x_; -} -inline void PointCloudXYZI_PointXYZI::set_x(float value) { - set_has_x(); - x_ = value; -} - -// required float y = 2; -inline bool PointCloudXYZI_PointXYZI::has_y() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void PointCloudXYZI_PointXYZI::set_has_y() { - _has_bits_[0] |= 0x00000002u; -} -inline void PointCloudXYZI_PointXYZI::clear_has_y() { - _has_bits_[0] &= ~0x00000002u; -} -inline void PointCloudXYZI_PointXYZI::clear_y() { - y_ = 0; - clear_has_y(); -} -inline float PointCloudXYZI_PointXYZI::y() const { - return y_; -} -inline void PointCloudXYZI_PointXYZI::set_y(float value) { - set_has_y(); - y_ = value; -} - -// required float z = 3; -inline bool PointCloudXYZI_PointXYZI::has_z() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void PointCloudXYZI_PointXYZI::set_has_z() { - _has_bits_[0] |= 0x00000004u; -} -inline void PointCloudXYZI_PointXYZI::clear_has_z() { - _has_bits_[0] &= ~0x00000004u; -} -inline void PointCloudXYZI_PointXYZI::clear_z() { - z_ = 0; - clear_has_z(); -} -inline float PointCloudXYZI_PointXYZI::z() const { - return z_; -} -inline void PointCloudXYZI_PointXYZI::set_z(float value) { - set_has_z(); - z_ = value; -} - -// required float intensity = 4; -inline bool PointCloudXYZI_PointXYZI::has_intensity() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void PointCloudXYZI_PointXYZI::set_has_intensity() { - _has_bits_[0] |= 0x00000008u; -} -inline void PointCloudXYZI_PointXYZI::clear_has_intensity() { - _has_bits_[0] &= ~0x00000008u; -} -inline void PointCloudXYZI_PointXYZI::clear_intensity() { - intensity_ = 0; - clear_has_intensity(); -} -inline float PointCloudXYZI_PointXYZI::intensity() const { - return intensity_; -} -inline void PointCloudXYZI_PointXYZI::set_intensity(float value) { - set_has_intensity(); - intensity_ = value; -} - -// ------------------------------------------------------------------- - -// PointCloudXYZI - -// required .px.HeaderInfo header = 1; -inline bool PointCloudXYZI::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void PointCloudXYZI::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void PointCloudXYZI::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void PointCloudXYZI::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& PointCloudXYZI::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* PointCloudXYZI::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* PointCloudXYZI::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// repeated .px.PointCloudXYZI.PointXYZI points = 2; -inline int PointCloudXYZI::points_size() const { - return points_.size(); -} -inline void PointCloudXYZI::clear_points() { - points_.Clear(); -} -inline const ::px::PointCloudXYZI_PointXYZI& PointCloudXYZI::points(int index) const { - return points_.Get(index); -} -inline ::px::PointCloudXYZI_PointXYZI* PointCloudXYZI::mutable_points(int index) { - return points_.Mutable(index); -} -inline ::px::PointCloudXYZI_PointXYZI* PointCloudXYZI::add_points() { - return points_.Add(); -} -inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >& -PointCloudXYZI::points() const { - return points_; -} -inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >* -PointCloudXYZI::mutable_points() { - return &points_; -} - -// ------------------------------------------------------------------- - -// PointCloudXYZRGB_PointXYZRGB - -// required float x = 1; -inline bool PointCloudXYZRGB_PointXYZRGB::has_x() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_has_x() { - _has_bits_[0] |= 0x00000001u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_has_x() { - _has_bits_[0] &= ~0x00000001u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_x() { - x_ = 0; - clear_has_x(); -} -inline float PointCloudXYZRGB_PointXYZRGB::x() const { - return x_; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_x(float value) { - set_has_x(); - x_ = value; -} - -// required float y = 2; -inline bool PointCloudXYZRGB_PointXYZRGB::has_y() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_has_y() { - _has_bits_[0] |= 0x00000002u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_has_y() { - _has_bits_[0] &= ~0x00000002u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_y() { - y_ = 0; - clear_has_y(); -} -inline float PointCloudXYZRGB_PointXYZRGB::y() const { - return y_; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_y(float value) { - set_has_y(); - y_ = value; -} - -// required float z = 3; -inline bool PointCloudXYZRGB_PointXYZRGB::has_z() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_has_z() { - _has_bits_[0] |= 0x00000004u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_has_z() { - _has_bits_[0] &= ~0x00000004u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_z() { - z_ = 0; - clear_has_z(); -} -inline float PointCloudXYZRGB_PointXYZRGB::z() const { - return z_; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_z(float value) { - set_has_z(); - z_ = value; -} - -// required float rgb = 4; -inline bool PointCloudXYZRGB_PointXYZRGB::has_rgb() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_has_rgb() { - _has_bits_[0] |= 0x00000008u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_has_rgb() { - _has_bits_[0] &= ~0x00000008u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_rgb() { - rgb_ = 0; - clear_has_rgb(); -} -inline float PointCloudXYZRGB_PointXYZRGB::rgb() const { - return rgb_; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_rgb(float value) { - set_has_rgb(); - rgb_ = value; -} - -// ------------------------------------------------------------------- - -// PointCloudXYZRGB - -// required .px.HeaderInfo header = 1; -inline bool PointCloudXYZRGB::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void PointCloudXYZRGB::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void PointCloudXYZRGB::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void PointCloudXYZRGB::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& PointCloudXYZRGB::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* PointCloudXYZRGB::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* PointCloudXYZRGB::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; -inline int PointCloudXYZRGB::points_size() const { - return points_.size(); -} -inline void PointCloudXYZRGB::clear_points() { - points_.Clear(); -} -inline const ::px::PointCloudXYZRGB_PointXYZRGB& PointCloudXYZRGB::points(int index) const { - return points_.Get(index); -} -inline ::px::PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB::mutable_points(int index) { - return points_.Mutable(index); -} -inline ::px::PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB::add_points() { - return points_.Add(); -} -inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >& -PointCloudXYZRGB::points() const { - return points_; -} -inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >* -PointCloudXYZRGB::mutable_points() { - return &points_; -} - -// ------------------------------------------------------------------- - -// RGBDImage - -// required .px.HeaderInfo header = 1; -inline bool RGBDImage::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void RGBDImage::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void RGBDImage::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void RGBDImage::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& RGBDImage::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* RGBDImage::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* RGBDImage::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// required uint32 cols = 2; -inline bool RGBDImage::has_cols() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void RGBDImage::set_has_cols() { - _has_bits_[0] |= 0x00000002u; -} -inline void RGBDImage::clear_has_cols() { - _has_bits_[0] &= ~0x00000002u; -} -inline void RGBDImage::clear_cols() { - cols_ = 0u; - clear_has_cols(); -} -inline ::google::protobuf::uint32 RGBDImage::cols() const { - return cols_; -} -inline void RGBDImage::set_cols(::google::protobuf::uint32 value) { - set_has_cols(); - cols_ = value; -} - -// required uint32 rows = 3; -inline bool RGBDImage::has_rows() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void RGBDImage::set_has_rows() { - _has_bits_[0] |= 0x00000004u; -} -inline void RGBDImage::clear_has_rows() { - _has_bits_[0] &= ~0x00000004u; -} -inline void RGBDImage::clear_rows() { - rows_ = 0u; - clear_has_rows(); -} -inline ::google::protobuf::uint32 RGBDImage::rows() const { - return rows_; -} -inline void RGBDImage::set_rows(::google::protobuf::uint32 value) { - set_has_rows(); - rows_ = value; -} - -// required uint32 step1 = 4; -inline bool RGBDImage::has_step1() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void RGBDImage::set_has_step1() { - _has_bits_[0] |= 0x00000008u; -} -inline void RGBDImage::clear_has_step1() { - _has_bits_[0] &= ~0x00000008u; -} -inline void RGBDImage::clear_step1() { - step1_ = 0u; - clear_has_step1(); -} -inline ::google::protobuf::uint32 RGBDImage::step1() const { - return step1_; -} -inline void RGBDImage::set_step1(::google::protobuf::uint32 value) { - set_has_step1(); - step1_ = value; -} - -// required uint32 type1 = 5; -inline bool RGBDImage::has_type1() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void RGBDImage::set_has_type1() { - _has_bits_[0] |= 0x00000010u; -} -inline void RGBDImage::clear_has_type1() { - _has_bits_[0] &= ~0x00000010u; -} -inline void RGBDImage::clear_type1() { - type1_ = 0u; - clear_has_type1(); -} -inline ::google::protobuf::uint32 RGBDImage::type1() const { - return type1_; -} -inline void RGBDImage::set_type1(::google::protobuf::uint32 value) { - set_has_type1(); - type1_ = value; -} - -// required bytes imageData1 = 6; -inline bool RGBDImage::has_imagedata1() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void RGBDImage::set_has_imagedata1() { - _has_bits_[0] |= 0x00000020u; -} -inline void RGBDImage::clear_has_imagedata1() { - _has_bits_[0] &= ~0x00000020u; -} -inline void RGBDImage::clear_imagedata1() { - if (imagedata1_ != &::google::protobuf::internal::kEmptyString) { - imagedata1_->clear(); - } - clear_has_imagedata1(); -} -inline const ::std::string& RGBDImage::imagedata1() const { - return *imagedata1_; -} -inline void RGBDImage::set_imagedata1(const ::std::string& value) { - set_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - imagedata1_ = new ::std::string; - } - imagedata1_->assign(value); -} -inline void RGBDImage::set_imagedata1(const char* value) { - set_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - imagedata1_ = new ::std::string; - } - imagedata1_->assign(value); -} -inline void RGBDImage::set_imagedata1(const void* value, size_t size) { - set_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - imagedata1_ = new ::std::string; - } - imagedata1_->assign(reinterpret_cast(value), size); -} -inline ::std::string* RGBDImage::mutable_imagedata1() { - set_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - imagedata1_ = new ::std::string; - } - return imagedata1_; -} -inline ::std::string* RGBDImage::release_imagedata1() { - clear_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = imagedata1_; - imagedata1_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// required uint32 step2 = 7; -inline bool RGBDImage::has_step2() const { - return (_has_bits_[0] & 0x00000040u) != 0; -} -inline void RGBDImage::set_has_step2() { - _has_bits_[0] |= 0x00000040u; -} -inline void RGBDImage::clear_has_step2() { - _has_bits_[0] &= ~0x00000040u; -} -inline void RGBDImage::clear_step2() { - step2_ = 0u; - clear_has_step2(); -} -inline ::google::protobuf::uint32 RGBDImage::step2() const { - return step2_; -} -inline void RGBDImage::set_step2(::google::protobuf::uint32 value) { - set_has_step2(); - step2_ = value; -} - -// required uint32 type2 = 8; -inline bool RGBDImage::has_type2() const { - return (_has_bits_[0] & 0x00000080u) != 0; -} -inline void RGBDImage::set_has_type2() { - _has_bits_[0] |= 0x00000080u; -} -inline void RGBDImage::clear_has_type2() { - _has_bits_[0] &= ~0x00000080u; -} -inline void RGBDImage::clear_type2() { - type2_ = 0u; - clear_has_type2(); -} -inline ::google::protobuf::uint32 RGBDImage::type2() const { - return type2_; -} -inline void RGBDImage::set_type2(::google::protobuf::uint32 value) { - set_has_type2(); - type2_ = value; -} - -// required bytes imageData2 = 9; -inline bool RGBDImage::has_imagedata2() const { - return (_has_bits_[0] & 0x00000100u) != 0; -} -inline void RGBDImage::set_has_imagedata2() { - _has_bits_[0] |= 0x00000100u; -} -inline void RGBDImage::clear_has_imagedata2() { - _has_bits_[0] &= ~0x00000100u; -} -inline void RGBDImage::clear_imagedata2() { - if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { - imagedata2_->clear(); - } - clear_has_imagedata2(); -} -inline const ::std::string& RGBDImage::imagedata2() const { - return *imagedata2_; -} -inline void RGBDImage::set_imagedata2(const ::std::string& value) { - set_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - imagedata2_ = new ::std::string; - } - imagedata2_->assign(value); -} -inline void RGBDImage::set_imagedata2(const char* value) { - set_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - imagedata2_ = new ::std::string; - } - imagedata2_->assign(value); -} -inline void RGBDImage::set_imagedata2(const void* value, size_t size) { - set_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - imagedata2_ = new ::std::string; - } - imagedata2_->assign(reinterpret_cast(value), size); -} -inline ::std::string* RGBDImage::mutable_imagedata2() { - set_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - imagedata2_ = new ::std::string; - } - return imagedata2_; -} -inline ::std::string* RGBDImage::release_imagedata2() { - clear_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = imagedata2_; - imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// optional uint32 camera_config = 10; -inline bool RGBDImage::has_camera_config() const { - return (_has_bits_[0] & 0x00000200u) != 0; -} -inline void RGBDImage::set_has_camera_config() { - _has_bits_[0] |= 0x00000200u; -} -inline void RGBDImage::clear_has_camera_config() { - _has_bits_[0] &= ~0x00000200u; -} -inline void RGBDImage::clear_camera_config() { - camera_config_ = 0u; - clear_has_camera_config(); -} -inline ::google::protobuf::uint32 RGBDImage::camera_config() const { - return camera_config_; -} -inline void RGBDImage::set_camera_config(::google::protobuf::uint32 value) { - set_has_camera_config(); - camera_config_ = value; -} - -// optional uint32 camera_type = 11; -inline bool RGBDImage::has_camera_type() const { - return (_has_bits_[0] & 0x00000400u) != 0; -} -inline void RGBDImage::set_has_camera_type() { - _has_bits_[0] |= 0x00000400u; -} -inline void RGBDImage::clear_has_camera_type() { - _has_bits_[0] &= ~0x00000400u; -} -inline void RGBDImage::clear_camera_type() { - camera_type_ = 0u; - clear_has_camera_type(); -} -inline ::google::protobuf::uint32 RGBDImage::camera_type() const { - return camera_type_; -} -inline void RGBDImage::set_camera_type(::google::protobuf::uint32 value) { - set_has_camera_type(); - camera_type_ = value; -} - -// optional float roll = 12; -inline bool RGBDImage::has_roll() const { - return (_has_bits_[0] & 0x00000800u) != 0; -} -inline void RGBDImage::set_has_roll() { - _has_bits_[0] |= 0x00000800u; -} -inline void RGBDImage::clear_has_roll() { - _has_bits_[0] &= ~0x00000800u; -} -inline void RGBDImage::clear_roll() { - roll_ = 0; - clear_has_roll(); -} -inline float RGBDImage::roll() const { - return roll_; -} -inline void RGBDImage::set_roll(float value) { - set_has_roll(); - roll_ = value; -} - -// optional float pitch = 13; -inline bool RGBDImage::has_pitch() const { - return (_has_bits_[0] & 0x00001000u) != 0; -} -inline void RGBDImage::set_has_pitch() { - _has_bits_[0] |= 0x00001000u; -} -inline void RGBDImage::clear_has_pitch() { - _has_bits_[0] &= ~0x00001000u; -} -inline void RGBDImage::clear_pitch() { - pitch_ = 0; - clear_has_pitch(); -} -inline float RGBDImage::pitch() const { - return pitch_; -} -inline void RGBDImage::set_pitch(float value) { - set_has_pitch(); - pitch_ = value; -} - -// optional float yaw = 14; -inline bool RGBDImage::has_yaw() const { - return (_has_bits_[0] & 0x00002000u) != 0; -} -inline void RGBDImage::set_has_yaw() { - _has_bits_[0] |= 0x00002000u; -} -inline void RGBDImage::clear_has_yaw() { - _has_bits_[0] &= ~0x00002000u; -} -inline void RGBDImage::clear_yaw() { - yaw_ = 0; - clear_has_yaw(); -} -inline float RGBDImage::yaw() const { - return yaw_; -} -inline void RGBDImage::set_yaw(float value) { - set_has_yaw(); - yaw_ = value; -} - -// optional float lon = 15; -inline bool RGBDImage::has_lon() const { - return (_has_bits_[0] & 0x00004000u) != 0; -} -inline void RGBDImage::set_has_lon() { - _has_bits_[0] |= 0x00004000u; -} -inline void RGBDImage::clear_has_lon() { - _has_bits_[0] &= ~0x00004000u; -} -inline void RGBDImage::clear_lon() { - lon_ = 0; - clear_has_lon(); -} -inline float RGBDImage::lon() const { - return lon_; -} -inline void RGBDImage::set_lon(float value) { - set_has_lon(); - lon_ = value; -} - -// optional float lat = 16; -inline bool RGBDImage::has_lat() const { - return (_has_bits_[0] & 0x00008000u) != 0; -} -inline void RGBDImage::set_has_lat() { - _has_bits_[0] |= 0x00008000u; -} -inline void RGBDImage::clear_has_lat() { - _has_bits_[0] &= ~0x00008000u; -} -inline void RGBDImage::clear_lat() { - lat_ = 0; - clear_has_lat(); -} -inline float RGBDImage::lat() const { - return lat_; -} -inline void RGBDImage::set_lat(float value) { - set_has_lat(); - lat_ = value; -} - -// optional float alt = 17; -inline bool RGBDImage::has_alt() const { - return (_has_bits_[0] & 0x00010000u) != 0; -} -inline void RGBDImage::set_has_alt() { - _has_bits_[0] |= 0x00010000u; -} -inline void RGBDImage::clear_has_alt() { - _has_bits_[0] &= ~0x00010000u; -} -inline void RGBDImage::clear_alt() { - alt_ = 0; - clear_has_alt(); -} -inline float RGBDImage::alt() const { - return alt_; -} -inline void RGBDImage::set_alt(float value) { - set_has_alt(); - alt_ = value; -} - -// optional float ground_x = 18; -inline bool RGBDImage::has_ground_x() const { - return (_has_bits_[0] & 0x00020000u) != 0; -} -inline void RGBDImage::set_has_ground_x() { - _has_bits_[0] |= 0x00020000u; -} -inline void RGBDImage::clear_has_ground_x() { - _has_bits_[0] &= ~0x00020000u; -} -inline void RGBDImage::clear_ground_x() { - ground_x_ = 0; - clear_has_ground_x(); -} -inline float RGBDImage::ground_x() const { - return ground_x_; -} -inline void RGBDImage::set_ground_x(float value) { - set_has_ground_x(); - ground_x_ = value; -} - -// optional float ground_y = 19; -inline bool RGBDImage::has_ground_y() const { - return (_has_bits_[0] & 0x00040000u) != 0; -} -inline void RGBDImage::set_has_ground_y() { - _has_bits_[0] |= 0x00040000u; -} -inline void RGBDImage::clear_has_ground_y() { - _has_bits_[0] &= ~0x00040000u; -} -inline void RGBDImage::clear_ground_y() { - ground_y_ = 0; - clear_has_ground_y(); -} -inline float RGBDImage::ground_y() const { - return ground_y_; -} -inline void RGBDImage::set_ground_y(float value) { - set_has_ground_y(); - ground_y_ = value; -} - -// optional float ground_z = 20; -inline bool RGBDImage::has_ground_z() const { - return (_has_bits_[0] & 0x00080000u) != 0; -} -inline void RGBDImage::set_has_ground_z() { - _has_bits_[0] |= 0x00080000u; -} -inline void RGBDImage::clear_has_ground_z() { - _has_bits_[0] &= ~0x00080000u; -} -inline void RGBDImage::clear_ground_z() { - ground_z_ = 0; - clear_has_ground_z(); -} -inline float RGBDImage::ground_z() const { - return ground_z_; -} -inline void RGBDImage::set_ground_z(float value) { - set_has_ground_z(); - ground_z_ = value; -} - -// repeated float camera_matrix = 21; -inline int RGBDImage::camera_matrix_size() const { - return camera_matrix_.size(); -} -inline void RGBDImage::clear_camera_matrix() { - camera_matrix_.Clear(); -} -inline float RGBDImage::camera_matrix(int index) const { - return camera_matrix_.Get(index); -} -inline void RGBDImage::set_camera_matrix(int index, float value) { - camera_matrix_.Set(index, value); -} -inline void RGBDImage::add_camera_matrix(float value) { - camera_matrix_.Add(value); -} -inline const ::google::protobuf::RepeatedField< float >& -RGBDImage::camera_matrix() const { - return camera_matrix_; -} -inline ::google::protobuf::RepeatedField< float >* -RGBDImage::mutable_camera_matrix() { - return &camera_matrix_; -} - -// ------------------------------------------------------------------- - -// Waypoint - -// required double x = 1; -inline bool Waypoint::has_x() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void Waypoint::set_has_x() { - _has_bits_[0] |= 0x00000001u; -} -inline void Waypoint::clear_has_x() { - _has_bits_[0] &= ~0x00000001u; -} -inline void Waypoint::clear_x() { - x_ = 0; - clear_has_x(); -} -inline double Waypoint::x() const { - return x_; -} -inline void Waypoint::set_x(double value) { - set_has_x(); - x_ = value; -} - -// required double y = 2; -inline bool Waypoint::has_y() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void Waypoint::set_has_y() { - _has_bits_[0] |= 0x00000002u; -} -inline void Waypoint::clear_has_y() { - _has_bits_[0] &= ~0x00000002u; -} -inline void Waypoint::clear_y() { - y_ = 0; - clear_has_y(); -} -inline double Waypoint::y() const { - return y_; -} -inline void Waypoint::set_y(double value) { - set_has_y(); - y_ = value; -} - -// optional double z = 3; -inline bool Waypoint::has_z() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void Waypoint::set_has_z() { - _has_bits_[0] |= 0x00000004u; -} -inline void Waypoint::clear_has_z() { - _has_bits_[0] &= ~0x00000004u; -} -inline void Waypoint::clear_z() { - z_ = 0; - clear_has_z(); -} -inline double Waypoint::z() const { - return z_; -} -inline void Waypoint::set_z(double value) { - set_has_z(); - z_ = value; -} - -// optional double roll = 4; -inline bool Waypoint::has_roll() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void Waypoint::set_has_roll() { - _has_bits_[0] |= 0x00000008u; -} -inline void Waypoint::clear_has_roll() { - _has_bits_[0] &= ~0x00000008u; -} -inline void Waypoint::clear_roll() { - roll_ = 0; - clear_has_roll(); -} -inline double Waypoint::roll() const { - return roll_; -} -inline void Waypoint::set_roll(double value) { - set_has_roll(); - roll_ = value; -} - -// optional double pitch = 5; -inline bool Waypoint::has_pitch() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void Waypoint::set_has_pitch() { - _has_bits_[0] |= 0x00000010u; -} -inline void Waypoint::clear_has_pitch() { - _has_bits_[0] &= ~0x00000010u; -} -inline void Waypoint::clear_pitch() { - pitch_ = 0; - clear_has_pitch(); -} -inline double Waypoint::pitch() const { - return pitch_; -} -inline void Waypoint::set_pitch(double value) { - set_has_pitch(); - pitch_ = value; -} - -// optional double yaw = 6; -inline bool Waypoint::has_yaw() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void Waypoint::set_has_yaw() { - _has_bits_[0] |= 0x00000020u; -} -inline void Waypoint::clear_has_yaw() { - _has_bits_[0] &= ~0x00000020u; -} -inline void Waypoint::clear_yaw() { - yaw_ = 0; - clear_has_yaw(); -} -inline double Waypoint::yaw() const { - return yaw_; -} -inline void Waypoint::set_yaw(double value) { - set_has_yaw(); - yaw_ = value; -} - - -// @@protoc_insertion_point(namespace_scope) - -} // namespace px - -#ifndef SWIG -namespace google { -namespace protobuf { - -template <> -inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_CoordinateFrameType>() { - return ::px::GLOverlay_CoordinateFrameType_descriptor(); -} -template <> -inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_Mode>() { - return ::px::GLOverlay_Mode_descriptor(); -} -template <> -inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_Identifier>() { - return ::px::GLOverlay_Identifier_descriptor(); -} - -} // namespace google -} // namespace protobuf -#endif // SWIG - -// @@protoc_insertion_point(global_scope) - -#endif // PROTOBUF_pixhawk_2eproto__INCLUDED diff --git a/mavlink/include/mavlink/v1.0/pixhawk/testsuite.h b/mavlink/include/mavlink/v1.0/pixhawk/testsuite.h deleted file mode 100644 index caa4d3dcb..000000000 --- a/mavlink/include/mavlink/v1.0/pixhawk/testsuite.h +++ /dev/null @@ -1,996 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from pixhawk.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef PIXHAWK_TESTSUITE_H -#define PIXHAWK_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); -static void mavlink_test_pixhawk(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_test_common(system_id, component_id, last_msg); - mavlink_test_pixhawk(system_id, component_id, last_msg); -} -#endif - -#include "../common/testsuite.h" - - -static void mavlink_test_set_cam_shutter(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_set_cam_shutter_t packet_in = { - 17.0, - }17443, - }17547, - }29, - }96, - }163, - }; - mavlink_set_cam_shutter_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.gain = packet_in.gain; - packet1.interval = packet_in.interval; - packet1.exposure = packet_in.exposure; - packet1.cam_no = packet_in.cam_no; - packet1.cam_mode = packet_in.cam_mode; - packet1.trigger_pin = packet_in.trigger_pin; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_cam_shutter_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_set_cam_shutter_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_cam_shutter_pack(system_id, component_id, &msg , packet1.cam_no , packet1.cam_mode , packet1.trigger_pin , packet1.interval , packet1.exposure , packet1.gain ); - mavlink_msg_set_cam_shutter_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_set_cam_shutter_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cam_no , packet1.cam_mode , packet1.trigger_pin , packet1.interval , packet1.exposure , packet1.gain ); - mavlink_msg_set_cam_shutter_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; ilen + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - -#if MAVLINK_NEED_BYTE_SWAP -static inline void byte_swap_2(char *dst, const char *src) -{ - dst[0] = src[1]; - dst[1] = src[0]; -} -static inline void byte_swap_4(char *dst, const char *src) -{ - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; -} -static inline void byte_swap_8(char *dst, const char *src) -{ - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; -} -#elif !MAVLINK_ALIGNED_FIELDS -static inline void byte_copy_2(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; -} -static inline void byte_copy_4(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; - dst[2] = src[2]; - dst[3] = src[3]; -} -static inline void byte_copy_8(char *dst, const char *src) -{ - memcpy(dst, src, 8); -} -#endif - -#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b -#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b -#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b - -#if MAVLINK_NEED_BYTE_SWAP -#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#elif !MAVLINK_ALIGNED_FIELDS -#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#else -#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b -#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b -#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b -#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b -#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b -#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b -#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b -#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b -#endif - -/* - like memcpy(), but if src is NULL, do a memset to zero -*/ -static inline void mav_array_memcpy(void *dest, const void *src, size_t n) -{ - if (src == NULL) { - memset(dest, 0, n); - } else { - memcpy(dest, src, n); - } -} - -/* - * Place a char array into a buffer - */ -static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a uint8_t array into a buffer - */ -static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a int8_t array into a buffer - */ -static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -#if MAVLINK_NEED_BYTE_SWAP -#define _MAV_PUT_ARRAY(TYPE, V) \ -static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ -{ \ - if (b == NULL) { \ - memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ - } else { \ - uint16_t i; \ - for (i=0; imsgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); -#endif -} - -/** - * @brief Pack a cmd_airspeed_ack message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param spCmd - - - * @param ack - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float spCmd,uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN]; - _mav_put_float(buf, 0, spCmd); - _mav_put_uint8_t(buf, 4, ack); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); -#else - mavlink_cmd_airspeed_ack_t packet; - packet.spCmd = spCmd; - packet.ack = ack; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); -#endif -} - -/** - * @brief Encode a cmd_airspeed_ack struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param cmd_airspeed_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack) -{ - return mavlink_msg_cmd_airspeed_ack_pack(system_id, component_id, msg, cmd_airspeed_ack->spCmd, cmd_airspeed_ack->ack); -} - -/** - * @brief Encode a cmd_airspeed_ack struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param cmd_airspeed_ack C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack) -{ - return mavlink_msg_cmd_airspeed_ack_pack_chan(system_id, component_id, chan, msg, cmd_airspeed_ack->spCmd, cmd_airspeed_ack->ack); -} - -/** - * @brief Send a cmd_airspeed_ack message - * @param chan MAVLink channel to send the message - * - * @param spCmd - - - * @param ack - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_cmd_airspeed_ack_send(mavlink_channel_t chan, float spCmd, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN]; - _mav_put_float(buf, 0, spCmd); - _mav_put_uint8_t(buf, 4, ack); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); -#endif -#else - mavlink_cmd_airspeed_ack_t packet; - packet.spCmd = spCmd; - packet.ack = ack; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)&packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)&packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_cmd_airspeed_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float spCmd, uint8_t ack) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, spCmd); - _mav_put_uint8_t(buf, 4, ack); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); -#endif -#else - mavlink_cmd_airspeed_ack_t *packet = (mavlink_cmd_airspeed_ack_t *)msgbuf; - packet->spCmd = spCmd; - packet->ack = ack; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)packet, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE CMD_AIRSPEED_ACK UNPACKING - - -/** - * @brief Get field spCmd from cmd_airspeed_ack message - * - * @return - - - */ -static inline float mavlink_msg_cmd_airspeed_ack_get_spCmd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field ack from cmd_airspeed_ack message - * - * @return - - - */ -static inline uint8_t mavlink_msg_cmd_airspeed_ack_get_ack(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Decode a cmd_airspeed_ack message into a struct - * - * @param msg The message to decode - * @param cmd_airspeed_ack C-struct to decode the message contents into - */ -static inline void mavlink_msg_cmd_airspeed_ack_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack) -{ -#if MAVLINK_NEED_BYTE_SWAP - cmd_airspeed_ack->spCmd = mavlink_msg_cmd_airspeed_ack_get_spCmd(msg); - cmd_airspeed_ack->ack = mavlink_msg_cmd_airspeed_ack_get_ack(msg); -#else - memcpy(cmd_airspeed_ack, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h deleted file mode 100644 index 71d61e1e0..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h +++ /dev/null @@ -1,253 +0,0 @@ -// MESSAGE CMD_AIRSPEED_CHNG PACKING - -#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG 192 - -typedef struct __mavlink_cmd_airspeed_chng_t -{ - float spCmd; ///< - - - uint8_t target; ///< - - -} mavlink_cmd_airspeed_chng_t; - -#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN 5 -#define MAVLINK_MSG_ID_192_LEN 5 - -#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC 209 -#define MAVLINK_MSG_ID_192_CRC 209 - - - -#define MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG { \ - "CMD_AIRSPEED_CHNG", \ - 2, \ - { { "spCmd", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_cmd_airspeed_chng_t, spCmd) }, \ - { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_cmd_airspeed_chng_t, target) }, \ - } \ -} - - -/** - * @brief Pack a cmd_airspeed_chng message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param target - - - * @param spCmd - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t target, float spCmd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN]; - _mav_put_float(buf, 0, spCmd); - _mav_put_uint8_t(buf, 4, target); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#else - mavlink_cmd_airspeed_chng_t packet; - packet.spCmd = spCmd; - packet.target = target; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#endif -} - -/** - * @brief Pack a cmd_airspeed_chng message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param target - - - * @param spCmd - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t target,float spCmd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN]; - _mav_put_float(buf, 0, spCmd); - _mav_put_uint8_t(buf, 4, target); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#else - mavlink_cmd_airspeed_chng_t packet; - packet.spCmd = spCmd; - packet.target = target; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#endif -} - -/** - * @brief Encode a cmd_airspeed_chng struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param cmd_airspeed_chng C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng) -{ - return mavlink_msg_cmd_airspeed_chng_pack(system_id, component_id, msg, cmd_airspeed_chng->target, cmd_airspeed_chng->spCmd); -} - -/** - * @brief Encode a cmd_airspeed_chng struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param cmd_airspeed_chng C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng) -{ - return mavlink_msg_cmd_airspeed_chng_pack_chan(system_id, component_id, chan, msg, cmd_airspeed_chng->target, cmd_airspeed_chng->spCmd); -} - -/** - * @brief Send a cmd_airspeed_chng message - * @param chan MAVLink channel to send the message - * - * @param target - - - * @param spCmd - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_cmd_airspeed_chng_send(mavlink_channel_t chan, uint8_t target, float spCmd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN]; - _mav_put_float(buf, 0, spCmd); - _mav_put_uint8_t(buf, 4, target); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#endif -#else - mavlink_cmd_airspeed_chng_t packet; - packet.spCmd = spCmd; - packet.target = target; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)&packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)&packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_cmd_airspeed_chng_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target, float spCmd) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, spCmd); - _mav_put_uint8_t(buf, 4, target); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#endif -#else - mavlink_cmd_airspeed_chng_t *packet = (mavlink_cmd_airspeed_chng_t *)msgbuf; - packet->spCmd = spCmd; - packet->target = target; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)packet, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE CMD_AIRSPEED_CHNG UNPACKING - - -/** - * @brief Get field target from cmd_airspeed_chng message - * - * @return - - - */ -static inline uint8_t mavlink_msg_cmd_airspeed_chng_get_target(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 4); -} - -/** - * @brief Get field spCmd from cmd_airspeed_chng message - * - * @return - - - */ -static inline float mavlink_msg_cmd_airspeed_chng_get_spCmd(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Decode a cmd_airspeed_chng message into a struct - * - * @param msg The message to decode - * @param cmd_airspeed_chng C-struct to decode the message contents into - */ -static inline void mavlink_msg_cmd_airspeed_chng_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng) -{ -#if MAVLINK_NEED_BYTE_SWAP - cmd_airspeed_chng->spCmd = mavlink_msg_cmd_airspeed_chng_get_spCmd(msg); - cmd_airspeed_chng->target = mavlink_msg_cmd_airspeed_chng_get_target(msg); -#else - memcpy(cmd_airspeed_chng, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h deleted file mode 100644 index 40a3db25a..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h +++ /dev/null @@ -1,219 +0,0 @@ -// MESSAGE FILT_ROT_VEL PACKING - -#define MAVLINK_MSG_ID_FILT_ROT_VEL 184 - -typedef struct __mavlink_filt_rot_vel_t -{ - float rotVel[3]; ///< - - -} mavlink_filt_rot_vel_t; - -#define MAVLINK_MSG_ID_FILT_ROT_VEL_LEN 12 -#define MAVLINK_MSG_ID_184_LEN 12 - -#define MAVLINK_MSG_ID_FILT_ROT_VEL_CRC 79 -#define MAVLINK_MSG_ID_184_CRC 79 - -#define MAVLINK_MSG_FILT_ROT_VEL_FIELD_ROTVEL_LEN 3 - -#define MAVLINK_MESSAGE_INFO_FILT_ROT_VEL { \ - "FILT_ROT_VEL", \ - 1, \ - { { "rotVel", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_filt_rot_vel_t, rotVel) }, \ - } \ -} - - -/** - * @brief Pack a filt_rot_vel message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param rotVel - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_filt_rot_vel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const float *rotVel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILT_ROT_VEL_LEN]; - - _mav_put_float_array(buf, 0, rotVel, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#else - mavlink_filt_rot_vel_t packet; - - mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#endif -} - -/** - * @brief Pack a filt_rot_vel message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param rotVel - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_filt_rot_vel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const float *rotVel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILT_ROT_VEL_LEN]; - - _mav_put_float_array(buf, 0, rotVel, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#else - mavlink_filt_rot_vel_t packet; - - mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#endif -} - -/** - * @brief Encode a filt_rot_vel struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param filt_rot_vel C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_filt_rot_vel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_filt_rot_vel_t* filt_rot_vel) -{ - return mavlink_msg_filt_rot_vel_pack(system_id, component_id, msg, filt_rot_vel->rotVel); -} - -/** - * @brief Encode a filt_rot_vel struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param filt_rot_vel C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_filt_rot_vel_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_filt_rot_vel_t* filt_rot_vel) -{ - return mavlink_msg_filt_rot_vel_pack_chan(system_id, component_id, chan, msg, filt_rot_vel->rotVel); -} - -/** - * @brief Send a filt_rot_vel message - * @param chan MAVLink channel to send the message - * - * @param rotVel - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_filt_rot_vel_send(mavlink_channel_t chan, const float *rotVel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_FILT_ROT_VEL_LEN]; - - _mav_put_float_array(buf, 0, rotVel, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#endif -#else - mavlink_filt_rot_vel_t packet; - - mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)&packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)&packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_FILT_ROT_VEL_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_filt_rot_vel_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const float *rotVel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_float_array(buf, 0, rotVel, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#endif -#else - mavlink_filt_rot_vel_t *packet = (mavlink_filt_rot_vel_t *)msgbuf; - - mav_array_memcpy(packet->rotVel, rotVel, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN, MAVLINK_MSG_ID_FILT_ROT_VEL_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)packet, MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE FILT_ROT_VEL UNPACKING - - -/** - * @brief Get field rotVel from filt_rot_vel message - * - * @return - - - */ -static inline uint16_t mavlink_msg_filt_rot_vel_get_rotVel(const mavlink_message_t* msg, float *rotVel) -{ - return _MAV_RETURN_float_array(msg, rotVel, 3, 0); -} - -/** - * @brief Decode a filt_rot_vel message into a struct - * - * @param msg The message to decode - * @param filt_rot_vel C-struct to decode the message contents into - */ -static inline void mavlink_msg_filt_rot_vel_decode(const mavlink_message_t* msg, mavlink_filt_rot_vel_t* filt_rot_vel) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_filt_rot_vel_get_rotVel(msg, filt_rot_vel->rotVel); -#else - memcpy(filt_rot_vel, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILT_ROT_VEL_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h deleted file mode 100644 index bceed1013..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h +++ /dev/null @@ -1,254 +0,0 @@ -// MESSAGE LLC_OUT PACKING - -#define MAVLINK_MSG_ID_LLC_OUT 186 - -typedef struct __mavlink_llc_out_t -{ - int16_t servoOut[4]; ///< - - - int16_t MotorOut[2]; ///< - - -} mavlink_llc_out_t; - -#define MAVLINK_MSG_ID_LLC_OUT_LEN 12 -#define MAVLINK_MSG_ID_186_LEN 12 - -#define MAVLINK_MSG_ID_LLC_OUT_CRC 5 -#define MAVLINK_MSG_ID_186_CRC 5 - -#define MAVLINK_MSG_LLC_OUT_FIELD_SERVOOUT_LEN 4 -#define MAVLINK_MSG_LLC_OUT_FIELD_MOTOROUT_LEN 2 - -#define MAVLINK_MESSAGE_INFO_LLC_OUT { \ - "LLC_OUT", \ - 2, \ - { { "servoOut", NULL, MAVLINK_TYPE_INT16_T, 4, 0, offsetof(mavlink_llc_out_t, servoOut) }, \ - { "MotorOut", NULL, MAVLINK_TYPE_INT16_T, 2, 8, offsetof(mavlink_llc_out_t, MotorOut) }, \ - } \ -} - - -/** - * @brief Pack a llc_out message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param servoOut - - - * @param MotorOut - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_llc_out_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const int16_t *servoOut, const int16_t *MotorOut) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LLC_OUT_LEN]; - - _mav_put_int16_t_array(buf, 0, servoOut, 4); - _mav_put_int16_t_array(buf, 8, MotorOut, 2); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LLC_OUT_LEN); -#else - mavlink_llc_out_t packet; - - mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4); - mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LLC_OUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LLC_OUT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LLC_OUT_LEN); -#endif -} - -/** - * @brief Pack a llc_out message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param servoOut - - - * @param MotorOut - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_llc_out_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const int16_t *servoOut,const int16_t *MotorOut) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LLC_OUT_LEN]; - - _mav_put_int16_t_array(buf, 0, servoOut, 4); - _mav_put_int16_t_array(buf, 8, MotorOut, 2); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LLC_OUT_LEN); -#else - mavlink_llc_out_t packet; - - mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4); - mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LLC_OUT_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_LLC_OUT; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LLC_OUT_LEN); -#endif -} - -/** - * @brief Encode a llc_out struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param llc_out C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_llc_out_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_llc_out_t* llc_out) -{ - return mavlink_msg_llc_out_pack(system_id, component_id, msg, llc_out->servoOut, llc_out->MotorOut); -} - -/** - * @brief Encode a llc_out struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param llc_out C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_llc_out_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_llc_out_t* llc_out) -{ - return mavlink_msg_llc_out_pack_chan(system_id, component_id, chan, msg, llc_out->servoOut, llc_out->MotorOut); -} - -/** - * @brief Send a llc_out message - * @param chan MAVLink channel to send the message - * - * @param servoOut - - - * @param MotorOut - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_llc_out_send(mavlink_channel_t chan, const int16_t *servoOut, const int16_t *MotorOut) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_LLC_OUT_LEN]; - - _mav_put_int16_t_array(buf, 0, servoOut, 4); - _mav_put_int16_t_array(buf, 8, MotorOut, 2); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, MAVLINK_MSG_ID_LLC_OUT_LEN); -#endif -#else - mavlink_llc_out_t packet; - - mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4); - mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)&packet, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)&packet, MAVLINK_MSG_ID_LLC_OUT_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_LLC_OUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_llc_out_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const int16_t *servoOut, const int16_t *MotorOut) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_int16_t_array(buf, 0, servoOut, 4); - _mav_put_int16_t_array(buf, 8, MotorOut, 2); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, MAVLINK_MSG_ID_LLC_OUT_LEN); -#endif -#else - mavlink_llc_out_t *packet = (mavlink_llc_out_t *)msgbuf; - - mav_array_memcpy(packet->servoOut, servoOut, sizeof(int16_t)*4); - mav_array_memcpy(packet->MotorOut, MotorOut, sizeof(int16_t)*2); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)packet, MAVLINK_MSG_ID_LLC_OUT_LEN, MAVLINK_MSG_ID_LLC_OUT_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)packet, MAVLINK_MSG_ID_LLC_OUT_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE LLC_OUT UNPACKING - - -/** - * @brief Get field servoOut from llc_out message - * - * @return - - - */ -static inline uint16_t mavlink_msg_llc_out_get_servoOut(const mavlink_message_t* msg, int16_t *servoOut) -{ - return _MAV_RETURN_int16_t_array(msg, servoOut, 4, 0); -} - -/** - * @brief Get field MotorOut from llc_out message - * - * @return - - - */ -static inline uint16_t mavlink_msg_llc_out_get_MotorOut(const mavlink_message_t* msg, int16_t *MotorOut) -{ - return _MAV_RETURN_int16_t_array(msg, MotorOut, 2, 8); -} - -/** - * @brief Decode a llc_out message into a struct - * - * @param msg The message to decode - * @param llc_out C-struct to decode the message contents into - */ -static inline void mavlink_msg_llc_out_decode(const mavlink_message_t* msg, mavlink_llc_out_t* llc_out) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_llc_out_get_servoOut(msg, llc_out->servoOut); - mavlink_msg_llc_out_get_MotorOut(msg, llc_out->MotorOut); -#else - memcpy(llc_out, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LLC_OUT_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h deleted file mode 100644 index f5a43e4fa..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h +++ /dev/null @@ -1,219 +0,0 @@ -// MESSAGE OBS_AIR_TEMP PACKING - -#define MAVLINK_MSG_ID_OBS_AIR_TEMP 183 - -typedef struct __mavlink_obs_air_temp_t -{ - float airT; ///< - - -} mavlink_obs_air_temp_t; - -#define MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN 4 -#define MAVLINK_MSG_ID_183_LEN 4 - -#define MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC 248 -#define MAVLINK_MSG_ID_183_CRC 248 - - - -#define MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP { \ - "OBS_AIR_TEMP", \ - 1, \ - { { "airT", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_obs_air_temp_t, airT) }, \ - } \ -} - - -/** - * @brief Pack a obs_air_temp message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param airT - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_air_temp_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float airT) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN]; - _mav_put_float(buf, 0, airT); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#else - mavlink_obs_air_temp_t packet; - packet.airT = airT; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#endif -} - -/** - * @brief Pack a obs_air_temp message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param airT - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_air_temp_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float airT) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN]; - _mav_put_float(buf, 0, airT); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#else - mavlink_obs_air_temp_t packet; - packet.airT = airT; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#endif -} - -/** - * @brief Encode a obs_air_temp struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param obs_air_temp C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_air_temp_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_temp_t* obs_air_temp) -{ - return mavlink_msg_obs_air_temp_pack(system_id, component_id, msg, obs_air_temp->airT); -} - -/** - * @brief Encode a obs_air_temp struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param obs_air_temp C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_air_temp_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_air_temp_t* obs_air_temp) -{ - return mavlink_msg_obs_air_temp_pack_chan(system_id, component_id, chan, msg, obs_air_temp->airT); -} - -/** - * @brief Send a obs_air_temp message - * @param chan MAVLink channel to send the message - * - * @param airT - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_obs_air_temp_send(mavlink_channel_t chan, float airT) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN]; - _mav_put_float(buf, 0, airT); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#endif -#else - mavlink_obs_air_temp_t packet; - packet.airT = airT; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)&packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)&packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_obs_air_temp_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float airT) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, airT); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#endif -#else - mavlink_obs_air_temp_t *packet = (mavlink_obs_air_temp_t *)msgbuf; - packet->airT = airT; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN, MAVLINK_MSG_ID_OBS_AIR_TEMP_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)packet, MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OBS_AIR_TEMP UNPACKING - - -/** - * @brief Get field airT from obs_air_temp message - * - * @return - - - */ -static inline float mavlink_msg_obs_air_temp_get_airT(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Decode a obs_air_temp message into a struct - * - * @param msg The message to decode - * @param obs_air_temp C-struct to decode the message contents into - */ -static inline void mavlink_msg_obs_air_temp_decode(const mavlink_message_t* msg, mavlink_obs_air_temp_t* obs_air_temp) -{ -#if MAVLINK_NEED_BYTE_SWAP - obs_air_temp->airT = mavlink_msg_obs_air_temp_get_airT(msg); -#else - memcpy(obs_air_temp, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h deleted file mode 100644 index 67d5ab2a2..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h +++ /dev/null @@ -1,287 +0,0 @@ -// MESSAGE OBS_AIR_VELOCITY PACKING - -#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY 178 - -typedef struct __mavlink_obs_air_velocity_t -{ - float magnitude; ///< - - - float aoa; ///< - - - float slip; ///< - - -} mavlink_obs_air_velocity_t; - -#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN 12 -#define MAVLINK_MSG_ID_178_LEN 12 - -#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC 32 -#define MAVLINK_MSG_ID_178_CRC 32 - - - -#define MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY { \ - "OBS_AIR_VELOCITY", \ - 3, \ - { { "magnitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_obs_air_velocity_t, magnitude) }, \ - { "aoa", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_obs_air_velocity_t, aoa) }, \ - { "slip", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_obs_air_velocity_t, slip) }, \ - } \ -} - - -/** - * @brief Pack a obs_air_velocity message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param magnitude - - - * @param aoa - - - * @param slip - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_air_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float magnitude, float aoa, float slip) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN]; - _mav_put_float(buf, 0, magnitude); - _mav_put_float(buf, 4, aoa); - _mav_put_float(buf, 8, slip); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#else - mavlink_obs_air_velocity_t packet; - packet.magnitude = magnitude; - packet.aoa = aoa; - packet.slip = slip; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#endif -} - -/** - * @brief Pack a obs_air_velocity message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param magnitude - - - * @param aoa - - - * @param slip - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_air_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float magnitude,float aoa,float slip) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN]; - _mav_put_float(buf, 0, magnitude); - _mav_put_float(buf, 4, aoa); - _mav_put_float(buf, 8, slip); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#else - mavlink_obs_air_velocity_t packet; - packet.magnitude = magnitude; - packet.aoa = aoa; - packet.slip = slip; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#endif -} - -/** - * @brief Encode a obs_air_velocity struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param obs_air_velocity C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_air_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_velocity_t* obs_air_velocity) -{ - return mavlink_msg_obs_air_velocity_pack(system_id, component_id, msg, obs_air_velocity->magnitude, obs_air_velocity->aoa, obs_air_velocity->slip); -} - -/** - * @brief Encode a obs_air_velocity struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param obs_air_velocity C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_air_velocity_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_air_velocity_t* obs_air_velocity) -{ - return mavlink_msg_obs_air_velocity_pack_chan(system_id, component_id, chan, msg, obs_air_velocity->magnitude, obs_air_velocity->aoa, obs_air_velocity->slip); -} - -/** - * @brief Send a obs_air_velocity message - * @param chan MAVLink channel to send the message - * - * @param magnitude - - - * @param aoa - - - * @param slip - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_obs_air_velocity_send(mavlink_channel_t chan, float magnitude, float aoa, float slip) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN]; - _mav_put_float(buf, 0, magnitude); - _mav_put_float(buf, 4, aoa); - _mav_put_float(buf, 8, slip); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#endif -#else - mavlink_obs_air_velocity_t packet; - packet.magnitude = magnitude; - packet.aoa = aoa; - packet.slip = slip; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)&packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)&packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_obs_air_velocity_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float magnitude, float aoa, float slip) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, magnitude); - _mav_put_float(buf, 4, aoa); - _mav_put_float(buf, 8, slip); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#endif -#else - mavlink_obs_air_velocity_t *packet = (mavlink_obs_air_velocity_t *)msgbuf; - packet->magnitude = magnitude; - packet->aoa = aoa; - packet->slip = slip; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)packet, MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OBS_AIR_VELOCITY UNPACKING - - -/** - * @brief Get field magnitude from obs_air_velocity message - * - * @return - - - */ -static inline float mavlink_msg_obs_air_velocity_get_magnitude(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field aoa from obs_air_velocity message - * - * @return - - - */ -static inline float mavlink_msg_obs_air_velocity_get_aoa(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field slip from obs_air_velocity message - * - * @return - - - */ -static inline float mavlink_msg_obs_air_velocity_get_slip(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 8); -} - -/** - * @brief Decode a obs_air_velocity message into a struct - * - * @param msg The message to decode - * @param obs_air_velocity C-struct to decode the message contents into - */ -static inline void mavlink_msg_obs_air_velocity_decode(const mavlink_message_t* msg, mavlink_obs_air_velocity_t* obs_air_velocity) -{ -#if MAVLINK_NEED_BYTE_SWAP - obs_air_velocity->magnitude = mavlink_msg_obs_air_velocity_get_magnitude(msg); - obs_air_velocity->aoa = mavlink_msg_obs_air_velocity_get_aoa(msg); - obs_air_velocity->slip = mavlink_msg_obs_air_velocity_get_slip(msg); -#else - memcpy(obs_air_velocity, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h deleted file mode 100644 index e1178e25f..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h +++ /dev/null @@ -1,219 +0,0 @@ -// MESSAGE OBS_ATTITUDE PACKING - -#define MAVLINK_MSG_ID_OBS_ATTITUDE 174 - -typedef struct __mavlink_obs_attitude_t -{ - double quat[4]; ///< - - -} mavlink_obs_attitude_t; - -#define MAVLINK_MSG_ID_OBS_ATTITUDE_LEN 32 -#define MAVLINK_MSG_ID_174_LEN 32 - -#define MAVLINK_MSG_ID_OBS_ATTITUDE_CRC 146 -#define MAVLINK_MSG_ID_174_CRC 146 - -#define MAVLINK_MSG_OBS_ATTITUDE_FIELD_QUAT_LEN 4 - -#define MAVLINK_MESSAGE_INFO_OBS_ATTITUDE { \ - "OBS_ATTITUDE", \ - 1, \ - { { "quat", NULL, MAVLINK_TYPE_DOUBLE, 4, 0, offsetof(mavlink_obs_attitude_t, quat) }, \ - } \ -} - - -/** - * @brief Pack a obs_attitude message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param quat - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const double *quat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_ATTITUDE_LEN]; - - _mav_put_double_array(buf, 0, quat, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#else - mavlink_obs_attitude_t packet; - - mav_array_memcpy(packet.quat, quat, sizeof(double)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#endif -} - -/** - * @brief Pack a obs_attitude message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param quat - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const double *quat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_ATTITUDE_LEN]; - - _mav_put_double_array(buf, 0, quat, 4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#else - mavlink_obs_attitude_t packet; - - mav_array_memcpy(packet.quat, quat, sizeof(double)*4); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#endif -} - -/** - * @brief Encode a obs_attitude struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param obs_attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_attitude_t* obs_attitude) -{ - return mavlink_msg_obs_attitude_pack(system_id, component_id, msg, obs_attitude->quat); -} - -/** - * @brief Encode a obs_attitude struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param obs_attitude C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_attitude_t* obs_attitude) -{ - return mavlink_msg_obs_attitude_pack_chan(system_id, component_id, chan, msg, obs_attitude->quat); -} - -/** - * @brief Send a obs_attitude message - * @param chan MAVLink channel to send the message - * - * @param quat - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const double *quat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_ATTITUDE_LEN]; - - _mav_put_double_array(buf, 0, quat, 4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#endif -#else - mavlink_obs_attitude_t packet; - - mav_array_memcpy(packet.quat, quat, sizeof(double)*4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OBS_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_obs_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const double *quat) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_double_array(buf, 0, quat, 4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#endif -#else - mavlink_obs_attitude_t *packet = (mavlink_obs_attitude_t *)msgbuf; - - mav_array_memcpy(packet->quat, quat, sizeof(double)*4); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN, MAVLINK_MSG_ID_OBS_ATTITUDE_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OBS_ATTITUDE UNPACKING - - -/** - * @brief Get field quat from obs_attitude message - * - * @return - - - */ -static inline uint16_t mavlink_msg_obs_attitude_get_quat(const mavlink_message_t* msg, double *quat) -{ - return _MAV_RETURN_double_array(msg, quat, 4, 0); -} - -/** - * @brief Decode a obs_attitude message into a struct - * - * @param msg The message to decode - * @param obs_attitude C-struct to decode the message contents into - */ -static inline void mavlink_msg_obs_attitude_decode(const mavlink_message_t* msg, mavlink_obs_attitude_t* obs_attitude) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_obs_attitude_get_quat(msg, obs_attitude->quat); -#else - memcpy(obs_attitude, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_ATTITUDE_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h deleted file mode 100644 index b164687ff..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h +++ /dev/null @@ -1,254 +0,0 @@ -// MESSAGE OBS_BIAS PACKING - -#define MAVLINK_MSG_ID_OBS_BIAS 180 - -typedef struct __mavlink_obs_bias_t -{ - float accBias[3]; ///< - - - float gyroBias[3]; ///< - - -} mavlink_obs_bias_t; - -#define MAVLINK_MSG_ID_OBS_BIAS_LEN 24 -#define MAVLINK_MSG_ID_180_LEN 24 - -#define MAVLINK_MSG_ID_OBS_BIAS_CRC 159 -#define MAVLINK_MSG_ID_180_CRC 159 - -#define MAVLINK_MSG_OBS_BIAS_FIELD_ACCBIAS_LEN 3 -#define MAVLINK_MSG_OBS_BIAS_FIELD_GYROBIAS_LEN 3 - -#define MAVLINK_MESSAGE_INFO_OBS_BIAS { \ - "OBS_BIAS", \ - 2, \ - { { "accBias", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_bias_t, accBias) }, \ - { "gyroBias", NULL, MAVLINK_TYPE_FLOAT, 3, 12, offsetof(mavlink_obs_bias_t, gyroBias) }, \ - } \ -} - - -/** - * @brief Pack a obs_bias message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param accBias - - - * @param gyroBias - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const float *accBias, const float *gyroBias) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_BIAS_LEN]; - - _mav_put_float_array(buf, 0, accBias, 3); - _mav_put_float_array(buf, 12, gyroBias, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#else - mavlink_obs_bias_t packet; - - mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3); - mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_BIAS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#endif -} - -/** - * @brief Pack a obs_bias message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param accBias - - - * @param gyroBias - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const float *accBias,const float *gyroBias) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_BIAS_LEN]; - - _mav_put_float_array(buf, 0, accBias, 3); - _mav_put_float_array(buf, 12, gyroBias, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#else - mavlink_obs_bias_t packet; - - mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3); - mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_BIAS; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#endif -} - -/** - * @brief Encode a obs_bias struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param obs_bias C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_bias_t* obs_bias) -{ - return mavlink_msg_obs_bias_pack(system_id, component_id, msg, obs_bias->accBias, obs_bias->gyroBias); -} - -/** - * @brief Encode a obs_bias struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param obs_bias C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_bias_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_bias_t* obs_bias) -{ - return mavlink_msg_obs_bias_pack_chan(system_id, component_id, chan, msg, obs_bias->accBias, obs_bias->gyroBias); -} - -/** - * @brief Send a obs_bias message - * @param chan MAVLink channel to send the message - * - * @param accBias - - - * @param gyroBias - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_obs_bias_send(mavlink_channel_t chan, const float *accBias, const float *gyroBias) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_BIAS_LEN]; - - _mav_put_float_array(buf, 0, accBias, 3); - _mav_put_float_array(buf, 12, gyroBias, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#endif -#else - mavlink_obs_bias_t packet; - - mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3); - mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)&packet, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)&packet, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OBS_BIAS_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_obs_bias_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const float *accBias, const float *gyroBias) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_float_array(buf, 0, accBias, 3); - _mav_put_float_array(buf, 12, gyroBias, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#endif -#else - mavlink_obs_bias_t *packet = (mavlink_obs_bias_t *)msgbuf; - - mav_array_memcpy(packet->accBias, accBias, sizeof(float)*3); - mav_array_memcpy(packet->gyroBias, gyroBias, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)packet, MAVLINK_MSG_ID_OBS_BIAS_LEN, MAVLINK_MSG_ID_OBS_BIAS_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)packet, MAVLINK_MSG_ID_OBS_BIAS_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OBS_BIAS UNPACKING - - -/** - * @brief Get field accBias from obs_bias message - * - * @return - - - */ -static inline uint16_t mavlink_msg_obs_bias_get_accBias(const mavlink_message_t* msg, float *accBias) -{ - return _MAV_RETURN_float_array(msg, accBias, 3, 0); -} - -/** - * @brief Get field gyroBias from obs_bias message - * - * @return - - - */ -static inline uint16_t mavlink_msg_obs_bias_get_gyroBias(const mavlink_message_t* msg, float *gyroBias) -{ - return _MAV_RETURN_float_array(msg, gyroBias, 3, 12); -} - -/** - * @brief Decode a obs_bias message into a struct - * - * @param msg The message to decode - * @param obs_bias C-struct to decode the message contents into - */ -static inline void mavlink_msg_obs_bias_decode(const mavlink_message_t* msg, mavlink_obs_bias_t* obs_bias) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_obs_bias_get_accBias(msg, obs_bias->accBias); - mavlink_msg_obs_bias_get_gyroBias(msg, obs_bias->gyroBias); -#else - memcpy(obs_bias, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_BIAS_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h deleted file mode 100644 index f0ecef0e7..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h +++ /dev/null @@ -1,287 +0,0 @@ -// MESSAGE OBS_POSITION PACKING - -#define MAVLINK_MSG_ID_OBS_POSITION 170 - -typedef struct __mavlink_obs_position_t -{ - int32_t lon; ///< - - - int32_t lat; ///< - - - int32_t alt; ///< - - -} mavlink_obs_position_t; - -#define MAVLINK_MSG_ID_OBS_POSITION_LEN 12 -#define MAVLINK_MSG_ID_170_LEN 12 - -#define MAVLINK_MSG_ID_OBS_POSITION_CRC 15 -#define MAVLINK_MSG_ID_170_CRC 15 - - - -#define MAVLINK_MESSAGE_INFO_OBS_POSITION { \ - "OBS_POSITION", \ - 3, \ - { { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_obs_position_t, lon) }, \ - { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_obs_position_t, lat) }, \ - { "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_obs_position_t, alt) }, \ - } \ -} - - -/** - * @brief Pack a obs_position message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param lon - - - * @param lat - - - * @param alt - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - int32_t lon, int32_t lat, int32_t alt) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_POSITION_LEN]; - _mav_put_int32_t(buf, 0, lon); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, alt); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#else - mavlink_obs_position_t packet; - packet.lon = lon; - packet.lat = lat; - packet.alt = alt; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_POSITION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#endif -} - -/** - * @brief Pack a obs_position message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param lon - - - * @param lat - - - * @param alt - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - int32_t lon,int32_t lat,int32_t alt) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_POSITION_LEN]; - _mav_put_int32_t(buf, 0, lon); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, alt); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#else - mavlink_obs_position_t packet; - packet.lon = lon; - packet.lat = lat; - packet.alt = alt; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_POSITION; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#endif -} - -/** - * @brief Encode a obs_position struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param obs_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_position_t* obs_position) -{ - return mavlink_msg_obs_position_pack(system_id, component_id, msg, obs_position->lon, obs_position->lat, obs_position->alt); -} - -/** - * @brief Encode a obs_position struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param obs_position C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_position_t* obs_position) -{ - return mavlink_msg_obs_position_pack_chan(system_id, component_id, chan, msg, obs_position->lon, obs_position->lat, obs_position->alt); -} - -/** - * @brief Send a obs_position message - * @param chan MAVLink channel to send the message - * - * @param lon - - - * @param lat - - - * @param alt - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_obs_position_send(mavlink_channel_t chan, int32_t lon, int32_t lat, int32_t alt) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_POSITION_LEN]; - _mav_put_int32_t(buf, 0, lon); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, alt); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#endif -#else - mavlink_obs_position_t packet; - packet.lon = lon; - packet.lat = lat; - packet.alt = alt; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)&packet, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)&packet, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OBS_POSITION_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_obs_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t lon, int32_t lat, int32_t alt) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_int32_t(buf, 0, lon); - _mav_put_int32_t(buf, 4, lat); - _mav_put_int32_t(buf, 8, alt); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#endif -#else - mavlink_obs_position_t *packet = (mavlink_obs_position_t *)msgbuf; - packet->lon = lon; - packet->lat = lat; - packet->alt = alt; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)packet, MAVLINK_MSG_ID_OBS_POSITION_LEN, MAVLINK_MSG_ID_OBS_POSITION_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)packet, MAVLINK_MSG_ID_OBS_POSITION_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OBS_POSITION UNPACKING - - -/** - * @brief Get field lon from obs_position message - * - * @return - - - */ -static inline int32_t mavlink_msg_obs_position_get_lon(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 0); -} - -/** - * @brief Get field lat from obs_position message - * - * @return - - - */ -static inline int32_t mavlink_msg_obs_position_get_lat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 4); -} - -/** - * @brief Get field alt from obs_position message - * - * @return - - - */ -static inline int32_t mavlink_msg_obs_position_get_alt(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 8); -} - -/** - * @brief Decode a obs_position message into a struct - * - * @param msg The message to decode - * @param obs_position C-struct to decode the message contents into - */ -static inline void mavlink_msg_obs_position_decode(const mavlink_message_t* msg, mavlink_obs_position_t* obs_position) -{ -#if MAVLINK_NEED_BYTE_SWAP - obs_position->lon = mavlink_msg_obs_position_get_lon(msg); - obs_position->lat = mavlink_msg_obs_position_get_lat(msg); - obs_position->alt = mavlink_msg_obs_position_get_alt(msg); -#else - memcpy(obs_position, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_POSITION_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h deleted file mode 100644 index 31617c883..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h +++ /dev/null @@ -1,219 +0,0 @@ -// MESSAGE OBS_QFF PACKING - -#define MAVLINK_MSG_ID_OBS_QFF 182 - -typedef struct __mavlink_obs_qff_t -{ - float qff; ///< - - -} mavlink_obs_qff_t; - -#define MAVLINK_MSG_ID_OBS_QFF_LEN 4 -#define MAVLINK_MSG_ID_182_LEN 4 - -#define MAVLINK_MSG_ID_OBS_QFF_CRC 24 -#define MAVLINK_MSG_ID_182_CRC 24 - - - -#define MAVLINK_MESSAGE_INFO_OBS_QFF { \ - "OBS_QFF", \ - 1, \ - { { "qff", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_obs_qff_t, qff) }, \ - } \ -} - - -/** - * @brief Pack a obs_qff message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param qff - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_qff_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float qff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_QFF_LEN]; - _mav_put_float(buf, 0, qff); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_QFF_LEN); -#else - mavlink_obs_qff_t packet; - packet.qff = qff; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_QFF_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_QFF; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_QFF_LEN); -#endif -} - -/** - * @brief Pack a obs_qff message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param qff - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_qff_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float qff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_QFF_LEN]; - _mav_put_float(buf, 0, qff); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_QFF_LEN); -#else - mavlink_obs_qff_t packet; - packet.qff = qff; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_QFF_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_QFF; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_QFF_LEN); -#endif -} - -/** - * @brief Encode a obs_qff struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param obs_qff C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_qff_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_qff_t* obs_qff) -{ - return mavlink_msg_obs_qff_pack(system_id, component_id, msg, obs_qff->qff); -} - -/** - * @brief Encode a obs_qff struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param obs_qff C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_qff_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_qff_t* obs_qff) -{ - return mavlink_msg_obs_qff_pack_chan(system_id, component_id, chan, msg, obs_qff->qff); -} - -/** - * @brief Send a obs_qff message - * @param chan MAVLink channel to send the message - * - * @param qff - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_obs_qff_send(mavlink_channel_t chan, float qff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_QFF_LEN]; - _mav_put_float(buf, 0, qff); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, MAVLINK_MSG_ID_OBS_QFF_LEN); -#endif -#else - mavlink_obs_qff_t packet; - packet.qff = qff; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)&packet, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)&packet, MAVLINK_MSG_ID_OBS_QFF_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OBS_QFF_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_obs_qff_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float qff) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, qff); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, MAVLINK_MSG_ID_OBS_QFF_LEN); -#endif -#else - mavlink_obs_qff_t *packet = (mavlink_obs_qff_t *)msgbuf; - packet->qff = qff; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)packet, MAVLINK_MSG_ID_OBS_QFF_LEN, MAVLINK_MSG_ID_OBS_QFF_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)packet, MAVLINK_MSG_ID_OBS_QFF_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OBS_QFF UNPACKING - - -/** - * @brief Get field qff from obs_qff message - * - * @return - - - */ -static inline float mavlink_msg_obs_qff_get_qff(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Decode a obs_qff message into a struct - * - * @param msg The message to decode - * @param obs_qff C-struct to decode the message contents into - */ -static inline void mavlink_msg_obs_qff_decode(const mavlink_message_t* msg, mavlink_obs_qff_t* obs_qff) -{ -#if MAVLINK_NEED_BYTE_SWAP - obs_qff->qff = mavlink_msg_obs_qff_get_qff(msg); -#else - memcpy(obs_qff, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_QFF_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h deleted file mode 100644 index ec815d692..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h +++ /dev/null @@ -1,219 +0,0 @@ -// MESSAGE OBS_VELOCITY PACKING - -#define MAVLINK_MSG_ID_OBS_VELOCITY 172 - -typedef struct __mavlink_obs_velocity_t -{ - float vel[3]; ///< - - -} mavlink_obs_velocity_t; - -#define MAVLINK_MSG_ID_OBS_VELOCITY_LEN 12 -#define MAVLINK_MSG_ID_172_LEN 12 - -#define MAVLINK_MSG_ID_OBS_VELOCITY_CRC 108 -#define MAVLINK_MSG_ID_172_CRC 108 - -#define MAVLINK_MSG_OBS_VELOCITY_FIELD_VEL_LEN 3 - -#define MAVLINK_MESSAGE_INFO_OBS_VELOCITY { \ - "OBS_VELOCITY", \ - 1, \ - { { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_velocity_t, vel) }, \ - } \ -} - - -/** - * @brief Pack a obs_velocity message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param vel - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const float *vel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_VELOCITY_LEN]; - - _mav_put_float_array(buf, 0, vel, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#else - mavlink_obs_velocity_t packet; - - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#endif -} - -/** - * @brief Pack a obs_velocity message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param vel - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const float *vel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_VELOCITY_LEN]; - - _mav_put_float_array(buf, 0, vel, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#else - mavlink_obs_velocity_t packet; - - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#endif -} - -/** - * @brief Encode a obs_velocity struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param obs_velocity C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_velocity_t* obs_velocity) -{ - return mavlink_msg_obs_velocity_pack(system_id, component_id, msg, obs_velocity->vel); -} - -/** - * @brief Encode a obs_velocity struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param obs_velocity C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_velocity_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_velocity_t* obs_velocity) -{ - return mavlink_msg_obs_velocity_pack_chan(system_id, component_id, chan, msg, obs_velocity->vel); -} - -/** - * @brief Send a obs_velocity message - * @param chan MAVLink channel to send the message - * - * @param vel - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_obs_velocity_send(mavlink_channel_t chan, const float *vel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_VELOCITY_LEN]; - - _mav_put_float_array(buf, 0, vel, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#endif -#else - mavlink_obs_velocity_t packet; - - mav_array_memcpy(packet.vel, vel, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)&packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)&packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OBS_VELOCITY_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_obs_velocity_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const float *vel) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_float_array(buf, 0, vel, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#endif -#else - mavlink_obs_velocity_t *packet = (mavlink_obs_velocity_t *)msgbuf; - - mav_array_memcpy(packet->vel, vel, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN, MAVLINK_MSG_ID_OBS_VELOCITY_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)packet, MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OBS_VELOCITY UNPACKING - - -/** - * @brief Get field vel from obs_velocity message - * - * @return - - - */ -static inline uint16_t mavlink_msg_obs_velocity_get_vel(const mavlink_message_t* msg, float *vel) -{ - return _MAV_RETURN_float_array(msg, vel, 3, 0); -} - -/** - * @brief Decode a obs_velocity message into a struct - * - * @param msg The message to decode - * @param obs_velocity C-struct to decode the message contents into - */ -static inline void mavlink_msg_obs_velocity_decode(const mavlink_message_t* msg, mavlink_obs_velocity_t* obs_velocity) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_obs_velocity_get_vel(msg, obs_velocity->vel); -#else - memcpy(obs_velocity, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_VELOCITY_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h deleted file mode 100644 index c40391d44..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h +++ /dev/null @@ -1,219 +0,0 @@ -// MESSAGE OBS_WIND PACKING - -#define MAVLINK_MSG_ID_OBS_WIND 176 - -typedef struct __mavlink_obs_wind_t -{ - float wind[3]; ///< - - -} mavlink_obs_wind_t; - -#define MAVLINK_MSG_ID_OBS_WIND_LEN 12 -#define MAVLINK_MSG_ID_176_LEN 12 - -#define MAVLINK_MSG_ID_OBS_WIND_CRC 16 -#define MAVLINK_MSG_ID_176_CRC 16 - -#define MAVLINK_MSG_OBS_WIND_FIELD_WIND_LEN 3 - -#define MAVLINK_MESSAGE_INFO_OBS_WIND { \ - "OBS_WIND", \ - 1, \ - { { "wind", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_wind_t, wind) }, \ - } \ -} - - -/** - * @brief Pack a obs_wind message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param wind - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - const float *wind) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_WIND_LEN]; - - _mav_put_float_array(buf, 0, wind, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_WIND_LEN); -#else - mavlink_obs_wind_t packet; - - mav_array_memcpy(packet.wind, wind, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_WIND_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_WIND; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBS_WIND_LEN); -#endif -} - -/** - * @brief Pack a obs_wind message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param wind - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_obs_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - const float *wind) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_WIND_LEN]; - - _mav_put_float_array(buf, 0, wind, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBS_WIND_LEN); -#else - mavlink_obs_wind_t packet; - - mav_array_memcpy(packet.wind, wind, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBS_WIND_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_OBS_WIND; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBS_WIND_LEN); -#endif -} - -/** - * @brief Encode a obs_wind struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param obs_wind C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_wind_t* obs_wind) -{ - return mavlink_msg_obs_wind_pack(system_id, component_id, msg, obs_wind->wind); -} - -/** - * @brief Encode a obs_wind struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param obs_wind C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_obs_wind_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obs_wind_t* obs_wind) -{ - return mavlink_msg_obs_wind_pack_chan(system_id, component_id, chan, msg, obs_wind->wind); -} - -/** - * @brief Send a obs_wind message - * @param chan MAVLink channel to send the message - * - * @param wind - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_obs_wind_send(mavlink_channel_t chan, const float *wind) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_OBS_WIND_LEN]; - - _mav_put_float_array(buf, 0, wind, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, MAVLINK_MSG_ID_OBS_WIND_LEN); -#endif -#else - mavlink_obs_wind_t packet; - - mav_array_memcpy(packet.wind, wind, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)&packet, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)&packet, MAVLINK_MSG_ID_OBS_WIND_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_OBS_WIND_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_obs_wind_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const float *wind) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - - _mav_put_float_array(buf, 0, wind, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, MAVLINK_MSG_ID_OBS_WIND_LEN); -#endif -#else - mavlink_obs_wind_t *packet = (mavlink_obs_wind_t *)msgbuf; - - mav_array_memcpy(packet->wind, wind, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)packet, MAVLINK_MSG_ID_OBS_WIND_LEN, MAVLINK_MSG_ID_OBS_WIND_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)packet, MAVLINK_MSG_ID_OBS_WIND_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE OBS_WIND UNPACKING - - -/** - * @brief Get field wind from obs_wind message - * - * @return - - - */ -static inline uint16_t mavlink_msg_obs_wind_get_wind(const mavlink_message_t* msg, float *wind) -{ - return _MAV_RETURN_float_array(msg, wind, 3, 0); -} - -/** - * @brief Decode a obs_wind message into a struct - * - * @param msg The message to decode - * @param obs_wind C-struct to decode the message contents into - */ -static inline void mavlink_msg_obs_wind_decode(const mavlink_message_t* msg, mavlink_obs_wind_t* obs_wind) -{ -#if MAVLINK_NEED_BYTE_SWAP - mavlink_msg_obs_wind_get_wind(msg, obs_wind->wind); -#else - memcpy(obs_wind, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OBS_WIND_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h deleted file mode 100644 index 70524f464..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h +++ /dev/null @@ -1,279 +0,0 @@ -// MESSAGE PM_ELEC PACKING - -#define MAVLINK_MSG_ID_PM_ELEC 188 - -typedef struct __mavlink_pm_elec_t -{ - float PwCons; ///< - - - float BatStat; ///< - - - float PwGen[3]; ///< - - -} mavlink_pm_elec_t; - -#define MAVLINK_MSG_ID_PM_ELEC_LEN 20 -#define MAVLINK_MSG_ID_188_LEN 20 - -#define MAVLINK_MSG_ID_PM_ELEC_CRC 170 -#define MAVLINK_MSG_ID_188_CRC 170 - -#define MAVLINK_MSG_PM_ELEC_FIELD_PWGEN_LEN 3 - -#define MAVLINK_MESSAGE_INFO_PM_ELEC { \ - "PM_ELEC", \ - 3, \ - { { "PwCons", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pm_elec_t, PwCons) }, \ - { "BatStat", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pm_elec_t, BatStat) }, \ - { "PwGen", NULL, MAVLINK_TYPE_FLOAT, 3, 8, offsetof(mavlink_pm_elec_t, PwGen) }, \ - } \ -} - - -/** - * @brief Pack a pm_elec message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param PwCons - - - * @param BatStat - - - * @param PwGen - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - float PwCons, float BatStat, const float *PwGen) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PM_ELEC_LEN]; - _mav_put_float(buf, 0, PwCons); - _mav_put_float(buf, 4, BatStat); - _mav_put_float_array(buf, 8, PwGen, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PM_ELEC_LEN); -#else - mavlink_pm_elec_t packet; - packet.PwCons = PwCons; - packet.BatStat = BatStat; - mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PM_ELEC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PM_ELEC; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PM_ELEC_LEN); -#endif -} - -/** - * @brief Pack a pm_elec message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param PwCons - - - * @param BatStat - - - * @param PwGen - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_pm_elec_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - float PwCons,float BatStat,const float *PwGen) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PM_ELEC_LEN]; - _mav_put_float(buf, 0, PwCons); - _mav_put_float(buf, 4, BatStat); - _mav_put_float_array(buf, 8, PwGen, 3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PM_ELEC_LEN); -#else - mavlink_pm_elec_t packet; - packet.PwCons = PwCons; - packet.BatStat = BatStat; - mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3); - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PM_ELEC_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_PM_ELEC; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PM_ELEC_LEN); -#endif -} - -/** - * @brief Encode a pm_elec struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param pm_elec C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_pm_elec_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pm_elec_t* pm_elec) -{ - return mavlink_msg_pm_elec_pack(system_id, component_id, msg, pm_elec->PwCons, pm_elec->BatStat, pm_elec->PwGen); -} - -/** - * @brief Encode a pm_elec struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param pm_elec C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_pm_elec_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pm_elec_t* pm_elec) -{ - return mavlink_msg_pm_elec_pack_chan(system_id, component_id, chan, msg, pm_elec->PwCons, pm_elec->BatStat, pm_elec->PwGen); -} - -/** - * @brief Send a pm_elec message - * @param chan MAVLink channel to send the message - * - * @param PwCons - - - * @param BatStat - - - * @param PwGen - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_pm_elec_send(mavlink_channel_t chan, float PwCons, float BatStat, const float *PwGen) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_PM_ELEC_LEN]; - _mav_put_float(buf, 0, PwCons); - _mav_put_float(buf, 4, BatStat); - _mav_put_float_array(buf, 8, PwGen, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, MAVLINK_MSG_ID_PM_ELEC_LEN); -#endif -#else - mavlink_pm_elec_t packet; - packet.PwCons = PwCons; - packet.BatStat = BatStat; - mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)&packet, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)&packet, MAVLINK_MSG_ID_PM_ELEC_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_PM_ELEC_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_pm_elec_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float PwCons, float BatStat, const float *PwGen) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_float(buf, 0, PwCons); - _mav_put_float(buf, 4, BatStat); - _mav_put_float_array(buf, 8, PwGen, 3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, MAVLINK_MSG_ID_PM_ELEC_LEN); -#endif -#else - mavlink_pm_elec_t *packet = (mavlink_pm_elec_t *)msgbuf; - packet->PwCons = PwCons; - packet->BatStat = BatStat; - mav_array_memcpy(packet->PwGen, PwGen, sizeof(float)*3); -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)packet, MAVLINK_MSG_ID_PM_ELEC_LEN, MAVLINK_MSG_ID_PM_ELEC_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)packet, MAVLINK_MSG_ID_PM_ELEC_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE PM_ELEC UNPACKING - - -/** - * @brief Get field PwCons from pm_elec message - * - * @return - - - */ -static inline float mavlink_msg_pm_elec_get_PwCons(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 0); -} - -/** - * @brief Get field BatStat from pm_elec message - * - * @return - - - */ -static inline float mavlink_msg_pm_elec_get_BatStat(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 4); -} - -/** - * @brief Get field PwGen from pm_elec message - * - * @return - - - */ -static inline uint16_t mavlink_msg_pm_elec_get_PwGen(const mavlink_message_t* msg, float *PwGen) -{ - return _MAV_RETURN_float_array(msg, PwGen, 3, 8); -} - -/** - * @brief Decode a pm_elec message into a struct - * - * @param msg The message to decode - * @param pm_elec C-struct to decode the message contents into - */ -static inline void mavlink_msg_pm_elec_decode(const mavlink_message_t* msg, mavlink_pm_elec_t* pm_elec) -{ -#if MAVLINK_NEED_BYTE_SWAP - pm_elec->PwCons = mavlink_msg_pm_elec_get_PwCons(msg); - pm_elec->BatStat = mavlink_msg_pm_elec_get_BatStat(msg); - mavlink_msg_pm_elec_get_PwGen(msg, pm_elec->PwGen); -#else - memcpy(pm_elec, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PM_ELEC_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h b/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h deleted file mode 100644 index 72f8a8193..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h +++ /dev/null @@ -1,321 +0,0 @@ -// MESSAGE SYS_Stat PACKING - -#define MAVLINK_MSG_ID_SYS_Stat 190 - -typedef struct __mavlink_sys_stat_t -{ - uint8_t gps; ///< - - - uint8_t act; ///< - - - uint8_t mod; ///< - - - uint8_t commRssi; ///< - - -} mavlink_sys_stat_t; - -#define MAVLINK_MSG_ID_SYS_Stat_LEN 4 -#define MAVLINK_MSG_ID_190_LEN 4 - -#define MAVLINK_MSG_ID_SYS_Stat_CRC 157 -#define MAVLINK_MSG_ID_190_CRC 157 - - - -#define MAVLINK_MESSAGE_INFO_SYS_Stat { \ - "SYS_Stat", \ - 4, \ - { { "gps", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sys_stat_t, gps) }, \ - { "act", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_sys_stat_t, act) }, \ - { "mod", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_sys_stat_t, mod) }, \ - { "commRssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_sys_stat_t, commRssi) }, \ - } \ -} - - -/** - * @brief Pack a sys_stat message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * - * @param gps - - - * @param act - - - * @param mod - - - * @param commRssi - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYS_Stat_LEN]; - _mav_put_uint8_t(buf, 0, gps); - _mav_put_uint8_t(buf, 1, act); - _mav_put_uint8_t(buf, 2, mod); - _mav_put_uint8_t(buf, 3, commRssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_Stat_LEN); -#else - mavlink_sys_stat_t packet; - packet.gps = gps; - packet.act = act; - packet.mod = mod; - packet.commRssi = commRssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_Stat_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYS_Stat; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); -#else - return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SYS_Stat_LEN); -#endif -} - -/** - * @brief Pack a sys_stat message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param gps - - - * @param act - - - * @param mod - - - * @param commRssi - - - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - uint8_t gps,uint8_t act,uint8_t mod,uint8_t commRssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYS_Stat_LEN]; - _mav_put_uint8_t(buf, 0, gps); - _mav_put_uint8_t(buf, 1, act); - _mav_put_uint8_t(buf, 2, mod); - _mav_put_uint8_t(buf, 3, commRssi); - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SYS_Stat_LEN); -#else - mavlink_sys_stat_t packet; - packet.gps = gps; - packet.act = act; - packet.mod = mod; - packet.commRssi = commRssi; - - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SYS_Stat_LEN); -#endif - - msg->msgid = MAVLINK_MSG_ID_SYS_Stat; -#if MAVLINK_CRC_EXTRA - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); -#else - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SYS_Stat_LEN); -#endif -} - -/** - * @brief Encode a sys_stat struct - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param sys_stat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_stat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_stat_t* sys_stat) -{ - return mavlink_msg_sys_stat_pack(system_id, component_id, msg, sys_stat->gps, sys_stat->act, sys_stat->mod, sys_stat->commRssi); -} - -/** - * @brief Encode a sys_stat struct on a channel - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message will be sent over - * @param msg The MAVLink message to compress the data into - * @param sys_stat C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_sys_stat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sys_stat_t* sys_stat) -{ - return mavlink_msg_sys_stat_pack_chan(system_id, component_id, chan, msg, sys_stat->gps, sys_stat->act, sys_stat->mod, sys_stat->commRssi); -} - -/** - * @brief Send a sys_stat message - * @param chan MAVLink channel to send the message - * - * @param gps - - - * @param act - - - * @param mod - - - * @param commRssi - - - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[MAVLINK_MSG_ID_SYS_Stat_LEN]; - _mav_put_uint8_t(buf, 0, gps); - _mav_put_uint8_t(buf, 1, act); - _mav_put_uint8_t(buf, 2, mod); - _mav_put_uint8_t(buf, 3, commRssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, MAVLINK_MSG_ID_SYS_Stat_LEN); -#endif -#else - mavlink_sys_stat_t packet; - packet.gps = gps; - packet.act = act; - packet.mod = mod; - packet.commRssi = commRssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)&packet, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)&packet, MAVLINK_MSG_ID_SYS_Stat_LEN); -#endif -#endif -} - -#if MAVLINK_MSG_ID_SYS_Stat_LEN <= MAVLINK_MAX_PAYLOAD_LEN -/* - This varient of _send() can be used to save stack space by re-using - memory from the receive buffer. The caller provides a - mavlink_message_t which is the size of a full mavlink message. This - is usually the receive buffer for the channel, and allows a reply to an - incoming message with minimum stack space usage. - */ -static inline void mavlink_msg_sys_stat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char *buf = (char *)msgbuf; - _mav_put_uint8_t(buf, 0, gps); - _mav_put_uint8_t(buf, 1, act); - _mav_put_uint8_t(buf, 2, mod); - _mav_put_uint8_t(buf, 3, commRssi); - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, MAVLINK_MSG_ID_SYS_Stat_LEN); -#endif -#else - mavlink_sys_stat_t *packet = (mavlink_sys_stat_t *)msgbuf; - packet->gps = gps; - packet->act = act; - packet->mod = mod; - packet->commRssi = commRssi; - -#if MAVLINK_CRC_EXTRA - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)packet, MAVLINK_MSG_ID_SYS_Stat_LEN, MAVLINK_MSG_ID_SYS_Stat_CRC); -#else - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)packet, MAVLINK_MSG_ID_SYS_Stat_LEN); -#endif -#endif -} -#endif - -#endif - -// MESSAGE SYS_Stat UNPACKING - - -/** - * @brief Get field gps from sys_stat message - * - * @return - - - */ -static inline uint8_t mavlink_msg_sys_stat_get_gps(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 0); -} - -/** - * @brief Get field act from sys_stat message - * - * @return - - - */ -static inline uint8_t mavlink_msg_sys_stat_get_act(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 1); -} - -/** - * @brief Get field mod from sys_stat message - * - * @return - - - */ -static inline uint8_t mavlink_msg_sys_stat_get_mod(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 2); -} - -/** - * @brief Get field commRssi from sys_stat message - * - * @return - - - */ -static inline uint8_t mavlink_msg_sys_stat_get_commRssi(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 3); -} - -/** - * @brief Decode a sys_stat message into a struct - * - * @param msg The message to decode - * @param sys_stat C-struct to decode the message contents into - */ -static inline void mavlink_msg_sys_stat_decode(const mavlink_message_t* msg, mavlink_sys_stat_t* sys_stat) -{ -#if MAVLINK_NEED_BYTE_SWAP - sys_stat->gps = mavlink_msg_sys_stat_get_gps(msg); - sys_stat->act = mavlink_msg_sys_stat_get_act(msg); - sys_stat->mod = mavlink_msg_sys_stat_get_mod(msg); - sys_stat->commRssi = mavlink_msg_sys_stat_get_commRssi(msg); -#else - memcpy(sys_stat, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SYS_Stat_LEN); -#endif -} diff --git a/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h b/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h deleted file mode 100644 index 2eab86354..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h +++ /dev/null @@ -1,77 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from sensesoar.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef SENSESOAR_H -#define SENSESOAR_H - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} -#endif - -#ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_SENSESOAR - -// ENUM DEFINITIONS - - -/** @brief Different flight modes */ -#ifndef HAVE_ENUM_SENSESOAR_MODE -#define HAVE_ENUM_SENSESOAR_MODE -enum SENSESOAR_MODE -{ - SENSESOAR_MODE_GLIDING=1, /* Gliding mode with motors off | */ - SENSESOAR_MODE_AUTONOMOUS=2, /* Autonomous flight | */ - SENSESOAR_MODE_MANUAL=3, /* RC controlled | */ - SENSESOAR_MODE_ENUM_END=4, /* | */ -}; -#endif - -#include "../common/common.h" - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 2 -#endif - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_obs_position.h" -#include "./mavlink_msg_obs_velocity.h" -#include "./mavlink_msg_obs_attitude.h" -#include "./mavlink_msg_obs_wind.h" -#include "./mavlink_msg_obs_air_velocity.h" -#include "./mavlink_msg_obs_bias.h" -#include "./mavlink_msg_obs_qff.h" -#include "./mavlink_msg_obs_air_temp.h" -#include "./mavlink_msg_filt_rot_vel.h" -#include "./mavlink_msg_llc_out.h" -#include "./mavlink_msg_pm_elec.h" -#include "./mavlink_msg_sys_stat.h" -#include "./mavlink_msg_cmd_airspeed_chng.h" -#include "./mavlink_msg_cmd_airspeed_ack.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // SENSESOAR_H diff --git a/mavlink/include/mavlink/v1.0/sensesoar/testsuite.h b/mavlink/include/mavlink/v1.0/sensesoar/testsuite.h deleted file mode 100644 index 67ffca799..000000000 --- a/mavlink/include/mavlink/v1.0/sensesoar/testsuite.h +++ /dev/null @@ -1,676 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from sensesoar.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef SENSESOAR_TESTSUITE_H -#define SENSESOAR_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL -static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg); -static void mavlink_test_sensesoar(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_test_common(system_id, component_id, last_msg); - mavlink_test_sensesoar(system_id, component_id, last_msg); -} -#endif - -#include "../common/testsuite.h" - - -static void mavlink_test_obs_position(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_obs_position_t packet_in = { - 963497464, - }963497672, - }963497880, - }; - mavlink_obs_position_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.lon = packet_in.lon; - packet1.lat = packet_in.lat; - packet1.alt = packet_in.alt; - - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_obs_position_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_obs_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_obs_position_pack(system_id, component_id, &msg , packet1.lon , packet1.lat , packet1.alt ); - mavlink_msg_obs_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_obs_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lon , packet1.lat , packet1.alt ); - mavlink_msg_obs_position_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; i Date: Wed, 2 Jul 2014 14:18:55 +0200 Subject: mavlink as git submodule Mavlink is now a git submodule because auto generated header files are available at https://github.com/mavlink/c_library --- .gitmodules | 3 +++ mavlink/include/mavlink/v1.0 | 1 + 2 files changed, 4 insertions(+) create mode 100644 .gitmodules create mode 160000 mavlink/include/mavlink/v1.0 diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 000000000..946a1fdcf --- /dev/null +++ b/.gitmodules @@ -0,0 +1,3 @@ +[submodule "mavlink/include/mavlink/v1.0"] + path = mavlink/include/mavlink/v1.0 + url = git@github.com:mavlink/c_library.git diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 new file mode 160000 index 000000000..45a71d656 --- /dev/null +++ b/mavlink/include/mavlink/v1.0 @@ -0,0 +1 @@ +Subproject commit 45a71d6564bc5c47ed97d620089e17ca48bab73f -- cgit v1.2.3 From 8f7fc27c5b6fe2dfe003ae1b421b83c23500415f Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 2 Jul 2014 15:40:28 +0200 Subject: sync with mavlink externalsetpoint branch https://github.com/mavlink/mavlink/commit/0d55cc7e886f6d3c824f8436a39b9f9b36d0458f --- .../mavlink/v1.0/ardupilotmega/ardupilotmega.h | 10 +- .../include/mavlink/v1.0/ardupilotmega/version.h | 2 +- mavlink/include/mavlink/v1.0/autoquad/autoquad.h | 6 +- mavlink/include/mavlink/v1.0/autoquad/version.h | 2 +- mavlink/include/mavlink/v1.0/common/common.h | 8 +- ...ink_msg_global_position_setpoint_external_int.h | 152 +++---- .../mavlink/v1.0/common/mavlink_msg_gps2_raw.h | 10 +- .../mavlink/v1.0/common/mavlink_msg_gps2_rtk.h | 497 +++++++++++++++++++++ .../mavlink/v1.0/common/mavlink_msg_gps_raw_int.h | 10 +- .../mavlink/v1.0/common/mavlink_msg_gps_rtk.h | 497 +++++++++++++++++++++ ...link_msg_local_ned_position_setpoint_external.h | 152 +++---- mavlink/include/mavlink/v1.0/common/testsuite.h | 164 ++++++- mavlink/include/mavlink/v1.0/common/version.h | 2 +- .../include/mavlink/v1.0/matrixpilot/matrixpilot.h | 6 +- mavlink/include/mavlink/v1.0/matrixpilot/version.h | 2 +- mavlink/include/mavlink/v1.0/pixhawk/pixhawk.h | 6 +- mavlink/include/mavlink/v1.0/pixhawk/version.h | 2 +- mavlink/include/mavlink/v1.0/sensesoar/sensesoar.h | 6 +- mavlink/include/mavlink/v1.0/sensesoar/version.h | 2 +- 19 files changed, 1335 insertions(+), 201 deletions(-) create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h create mode 100644 mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_rtk.h diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h index 7e9173247..d3213e7c9 100644 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h @@ -16,15 +16,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 41, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 44, 3, 9, 22, 12, 18, 34, 66, 98, 8, 48, 19, 3, 20, 24, 29, 41, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 212, 121, 172, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 206, 151, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 212, 211, 198, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 154, 21, 21, 144, 1, 234, 73, 181, 22, 83, 167, 138, 234, 240, 47, 206, 151, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, MAVLINK_MESSAGE_INFO_CAMERA_EVENT, MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, MAVLINK_MESSAGE_INFO_CAMERA_EVENT, MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" @@ -174,7 +174,9 @@ typedef enum CAMERA_FEEDBACK_FLAGS { VIDEO=1, /* Shooting video, not stills | */ BADEXPOSURE=2, /* Unable to achieve requested exposure (e.g. shutter speed too low) | */ - CAMERA_FEEDBACK_FLAGS_ENUM_END=3, /* | */ + CLOSEDLOOP=3, /* Closed loop feedback from camera, we know for sure it has successfully taken a picture | */ + OPENLOOP=4, /* Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture | */ + CAMERA_FEEDBACK_FLAGS_ENUM_END=5, /* | */ } CAMERA_FEEDBACK_FLAGS; #endif diff --git a/mavlink/include/mavlink/v1.0/ardupilotmega/version.h b/mavlink/include/mavlink/v1.0/ardupilotmega/version.h index 192d1cb01..32077820d 100644 --- a/mavlink/include/mavlink/v1.0/ardupilotmega/version.h +++ b/mavlink/include/mavlink/v1.0/ardupilotmega/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Jun 23 10:13:03 2014" +#define MAVLINK_BUILD_DATE "Wed Jul 2 15:36:07 2014" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/mavlink/include/mavlink/v1.0/autoquad/autoquad.h b/mavlink/include/mavlink/v1.0/autoquad/autoquad.h index 464994f86..0428100ca 100644 --- a/mavlink/include/mavlink/v1.0/autoquad/autoquad.h +++ b/mavlink/include/mavlink/v1.0/autoquad/autoquad.h @@ -16,15 +16,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 82, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 212, 121, 172, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 241, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 212, 211, 198, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 241, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_AQ_TELEMETRY_F, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, MAVLINK_MESSAGE_INFO_AQ_TELEMETRY_F, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" diff --git a/mavlink/include/mavlink/v1.0/autoquad/version.h b/mavlink/include/mavlink/v1.0/autoquad/version.h index ce27e3e53..3a6222d73 100644 --- a/mavlink/include/mavlink/v1.0/autoquad/version.h +++ b/mavlink/include/mavlink/v1.0/autoquad/version.h @@ -5,7 +5,7 @@ #ifndef MAVLINK_VERSION_H #define MAVLINK_VERSION_H -#define MAVLINK_BUILD_DATE "Mon Jun 23 10:13:13 2014" +#define MAVLINK_BUILD_DATE "Wed Jul 2 15:36:18 2014" #define MAVLINK_WIRE_PROTOCOL_VERSION "1.0" #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255 diff --git a/mavlink/include/mavlink/v1.0/common/common.h b/mavlink/include/mavlink/v1.0/common/common.h index 92186cc8a..f42c066a6 100644 --- a/mavlink/include/mavlink/v1.0/common/common.h +++ b/mavlink/include/mavlink/v1.0/common/common.h @@ -16,15 +16,15 @@ extern "C" { // MESSAGE LENGTHS AND CRCS #ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 0, 0, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} +#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 34, 26, 46, 36, 42, 6, 4, 0, 11, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 20, 22, 39, 45, 44, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 62, 54, 64, 84, 9, 254, 249, 9, 36, 26, 64, 22, 6, 14, 12, 97, 2, 2, 113, 35, 6, 79, 35, 35, 0, 13, 255, 14, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 24, 33, 25, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0} #endif #ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 212, 121, 172, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 0, 0, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} +#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 240, 183, 130, 130, 118, 148, 21, 0, 243, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 127, 106, 212, 211, 198, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 93, 211, 108, 32, 185, 235, 93, 124, 124, 119, 4, 76, 128, 56, 116, 134, 237, 203, 250, 87, 203, 220, 25, 226, 0, 29, 223, 85, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 177, 241, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0} #endif #ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} +#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_LED_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_ATTITUDE_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_LOCAL_NED_POSITION_SETPOINT_EXTERNAL, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OMNIDIRECTIONAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_START, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_DIR_LIST, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_RES, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_SETPOINT_8DOF, MAVLINK_MESSAGE_INFO_SETPOINT_6DOF, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}} #endif #include "../protocol.h" @@ -659,6 +659,8 @@ typedef enum MAV_DISTANCE_SENSOR #include "./mavlink_msg_gps2_raw.h" #include "./mavlink_msg_power_status.h" #include "./mavlink_msg_serial_control.h" +#include "./mavlink_msg_gps_rtk.h" +#include "./mavlink_msg_gps2_rtk.h" #include "./mavlink_msg_data_transmission_handshake.h" #include "./mavlink_msg_encapsulated_data.h" #include "./mavlink_msg_distance_sensor.h" diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_external_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_external_int.h index 46ab556d8..a383def66 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_external_int.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_external_int.h @@ -11,10 +11,10 @@ typedef struct __mavlink_global_position_setpoint_external_int_t float vx; ///< X velocity in NED frame in meter / s float vy; ///< Y velocity in NED frame in meter / s float vz; ///< Z velocity in NED frame in meter / s - float ax; ///< X acceleration in NED frame in meter / s^2 - float ay; ///< Y acceleration in NED frame in meter / s^2 - float az; ///< Z acceleration in NED frame in meter / s^2 - uint16_t ignore_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint uint8_t target_system; ///< System ID uint8_t target_component; ///< Component ID } mavlink_global_position_setpoint_external_int_t; @@ -22,8 +22,8 @@ typedef struct __mavlink_global_position_setpoint_external_int_t #define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN 44 #define MAVLINK_MSG_ID_84_LEN 44 -#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC 172 -#define MAVLINK_MSG_ID_84_CRC 172 +#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_CRC 198 +#define MAVLINK_MSG_ID_84_CRC 198 @@ -37,10 +37,10 @@ typedef struct __mavlink_global_position_setpoint_external_int_t { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_setpoint_external_int_t, vx) }, \ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_setpoint_external_int_t, vy) }, \ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_setpoint_external_int_t, vz) }, \ - { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_setpoint_external_int_t, ax) }, \ - { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_setpoint_external_int_t, ay) }, \ - { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_setpoint_external_int_t, az) }, \ - { "ignore_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_global_position_setpoint_external_int_t, ignore_mask) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_setpoint_external_int_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_setpoint_external_int_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_setpoint_external_int_t, afz) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_global_position_setpoint_external_int_t, type_mask) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_global_position_setpoint_external_int_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_global_position_setpoint_external_int_t, target_component) }, \ } \ @@ -56,20 +56,20 @@ typedef struct __mavlink_global_position_setpoint_external_int_t * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. * @param target_system System ID * @param target_component Component ID - * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint * @param lat_int X Position in WGS84 frame in 1e7 * meters * @param lon_int Y Position in WGS84 frame in 1e7 * meters * @param alt Altitude in WGS84, not AMSL * @param vx X velocity in NED frame in meter / s * @param vy Y velocity in NED frame in meter / s * @param vz Z velocity in NED frame in meter / s - * @param ax X acceleration in NED frame in meter / s^2 - * @param ay Y acceleration in NED frame in meter / s^2 - * @param az Z acceleration in NED frame in meter / s^2 + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint16_t ignore_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float ax, float ay, float az) + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN]; @@ -80,10 +80,10 @@ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack(ui _mav_put_float(buf, 16, vx); _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, ax); - _mav_put_float(buf, 32, ay); - _mav_put_float(buf, 36, az); - _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_uint16_t(buf, 40, type_mask); _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, target_component); @@ -97,10 +97,10 @@ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack(ui packet.vx = vx; packet.vy = vy; packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.ignore_mask = ignore_mask; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.type_mask = type_mask; packet.target_system = target_system; packet.target_component = target_component; @@ -124,21 +124,21 @@ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack(ui * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. * @param target_system System ID * @param target_component Component ID - * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint * @param lat_int X Position in WGS84 frame in 1e7 * meters * @param lon_int Y Position in WGS84 frame in 1e7 * meters * @param alt Altitude in WGS84, not AMSL * @param vx X velocity in NED frame in meter / s * @param vy Y velocity in NED frame in meter / s * @param vz Z velocity in NED frame in meter / s - * @param ax X acceleration in NED frame in meter / s^2 - * @param ay Y acceleration in NED frame in meter / s^2 - * @param az Z acceleration in NED frame in meter / s^2 + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint16_t ignore_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float ax,float ay,float az) + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN]; @@ -149,10 +149,10 @@ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack_ch _mav_put_float(buf, 16, vx); _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, ax); - _mav_put_float(buf, 32, ay); - _mav_put_float(buf, 36, az); - _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_uint16_t(buf, 40, type_mask); _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, target_component); @@ -166,10 +166,10 @@ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack_ch packet.vx = vx; packet.vy = vy; packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.ignore_mask = ignore_mask; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.type_mask = type_mask; packet.target_system = target_system; packet.target_component = target_component; @@ -194,7 +194,7 @@ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_pack_ch */ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_setpoint_external_int_t* global_position_setpoint_external_int) { - return mavlink_msg_global_position_setpoint_external_int_pack(system_id, component_id, msg, global_position_setpoint_external_int->time_boot_ms, global_position_setpoint_external_int->target_system, global_position_setpoint_external_int->target_component, global_position_setpoint_external_int->ignore_mask, global_position_setpoint_external_int->lat_int, global_position_setpoint_external_int->lon_int, global_position_setpoint_external_int->alt, global_position_setpoint_external_int->vx, global_position_setpoint_external_int->vy, global_position_setpoint_external_int->vz, global_position_setpoint_external_int->ax, global_position_setpoint_external_int->ay, global_position_setpoint_external_int->az); + return mavlink_msg_global_position_setpoint_external_int_pack(system_id, component_id, msg, global_position_setpoint_external_int->time_boot_ms, global_position_setpoint_external_int->target_system, global_position_setpoint_external_int->target_component, global_position_setpoint_external_int->type_mask, global_position_setpoint_external_int->lat_int, global_position_setpoint_external_int->lon_int, global_position_setpoint_external_int->alt, global_position_setpoint_external_int->vx, global_position_setpoint_external_int->vy, global_position_setpoint_external_int->vz, global_position_setpoint_external_int->afx, global_position_setpoint_external_int->afy, global_position_setpoint_external_int->afz); } /** @@ -208,7 +208,7 @@ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_encode( */ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_setpoint_external_int_t* global_position_setpoint_external_int) { - return mavlink_msg_global_position_setpoint_external_int_pack_chan(system_id, component_id, chan, msg, global_position_setpoint_external_int->time_boot_ms, global_position_setpoint_external_int->target_system, global_position_setpoint_external_int->target_component, global_position_setpoint_external_int->ignore_mask, global_position_setpoint_external_int->lat_int, global_position_setpoint_external_int->lon_int, global_position_setpoint_external_int->alt, global_position_setpoint_external_int->vx, global_position_setpoint_external_int->vy, global_position_setpoint_external_int->vz, global_position_setpoint_external_int->ax, global_position_setpoint_external_int->ay, global_position_setpoint_external_int->az); + return mavlink_msg_global_position_setpoint_external_int_pack_chan(system_id, component_id, chan, msg, global_position_setpoint_external_int->time_boot_ms, global_position_setpoint_external_int->target_system, global_position_setpoint_external_int->target_component, global_position_setpoint_external_int->type_mask, global_position_setpoint_external_int->lat_int, global_position_setpoint_external_int->lon_int, global_position_setpoint_external_int->alt, global_position_setpoint_external_int->vx, global_position_setpoint_external_int->vy, global_position_setpoint_external_int->vz, global_position_setpoint_external_int->afx, global_position_setpoint_external_int->afy, global_position_setpoint_external_int->afz); } /** @@ -218,20 +218,20 @@ static inline uint16_t mavlink_msg_global_position_setpoint_external_int_encode_ * @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency. * @param target_system System ID * @param target_component Component ID - * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint * @param lat_int X Position in WGS84 frame in 1e7 * meters * @param lon_int Y Position in WGS84 frame in 1e7 * meters * @param alt Altitude in WGS84, not AMSL * @param vx X velocity in NED frame in meter / s * @param vy Y velocity in NED frame in meter / s * @param vz Z velocity in NED frame in meter / s - * @param ax X acceleration in NED frame in meter / s^2 - * @param ay Y acceleration in NED frame in meter / s^2 - * @param az Z acceleration in NED frame in meter / s^2 + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_global_position_setpoint_external_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint16_t ignore_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float ax, float ay, float az) +static inline void mavlink_msg_global_position_setpoint_external_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_EXTERNAL_INT_LEN]; @@ -242,10 +242,10 @@ static inline void mavlink_msg_global_position_setpoint_external_int_send(mavlin _mav_put_float(buf, 16, vx); _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, ax); - _mav_put_float(buf, 32, ay); - _mav_put_float(buf, 36, az); - _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_uint16_t(buf, 40, type_mask); _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, target_component); @@ -263,10 +263,10 @@ static inline void mavlink_msg_global_position_setpoint_external_int_send(mavlin packet.vx = vx; packet.vy = vy; packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.ignore_mask = ignore_mask; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.type_mask = type_mask; packet.target_system = target_system; packet.target_component = target_component; @@ -286,7 +286,7 @@ static inline void mavlink_msg_global_position_setpoint_external_int_send(mavlin is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_global_position_setpoint_external_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint16_t ignore_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float ax, float ay, float az) +static inline void mavlink_msg_global_position_setpoint_external_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -297,10 +297,10 @@ static inline void mavlink_msg_global_position_setpoint_external_int_send_buf(ma _mav_put_float(buf, 16, vx); _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, ax); - _mav_put_float(buf, 32, ay); - _mav_put_float(buf, 36, az); - _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_uint16_t(buf, 40, type_mask); _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, target_component); @@ -318,10 +318,10 @@ static inline void mavlink_msg_global_position_setpoint_external_int_send_buf(ma packet->vx = vx; packet->vy = vy; packet->vz = vz; - packet->ax = ax; - packet->ay = ay; - packet->az = az; - packet->ignore_mask = ignore_mask; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->type_mask = type_mask; packet->target_system = target_system; packet->target_component = target_component; @@ -370,11 +370,11 @@ static inline uint8_t mavlink_msg_global_position_setpoint_external_int_get_targ } /** - * @brief Get field ignore_mask from global_position_setpoint_external_int message + * @brief Get field type_mask from global_position_setpoint_external_int message * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: lat, bit 2: lon, bit 3: alt, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint */ -static inline uint16_t mavlink_msg_global_position_setpoint_external_int_get_ignore_mask(const mavlink_message_t* msg) +static inline uint16_t mavlink_msg_global_position_setpoint_external_int_get_type_mask(const mavlink_message_t* msg) { return _MAV_RETURN_uint16_t(msg, 40); } @@ -440,31 +440,31 @@ static inline float mavlink_msg_global_position_setpoint_external_int_get_vz(con } /** - * @brief Get field ax from global_position_setpoint_external_int message + * @brief Get field afx from global_position_setpoint_external_int message * - * @return X acceleration in NED frame in meter / s^2 + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ -static inline float mavlink_msg_global_position_setpoint_external_int_get_ax(const mavlink_message_t* msg) +static inline float mavlink_msg_global_position_setpoint_external_int_get_afx(const mavlink_message_t* msg) { return _MAV_RETURN_float(msg, 28); } /** - * @brief Get field ay from global_position_setpoint_external_int message + * @brief Get field afy from global_position_setpoint_external_int message * - * @return Y acceleration in NED frame in meter / s^2 + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ -static inline float mavlink_msg_global_position_setpoint_external_int_get_ay(const mavlink_message_t* msg) +static inline float mavlink_msg_global_position_setpoint_external_int_get_afy(const mavlink_message_t* msg) { return _MAV_RETURN_float(msg, 32); } /** - * @brief Get field az from global_position_setpoint_external_int message + * @brief Get field afz from global_position_setpoint_external_int message * - * @return Z acceleration in NED frame in meter / s^2 + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ -static inline float mavlink_msg_global_position_setpoint_external_int_get_az(const mavlink_message_t* msg) +static inline float mavlink_msg_global_position_setpoint_external_int_get_afz(const mavlink_message_t* msg) { return _MAV_RETURN_float(msg, 36); } @@ -485,10 +485,10 @@ static inline void mavlink_msg_global_position_setpoint_external_int_decode(cons global_position_setpoint_external_int->vx = mavlink_msg_global_position_setpoint_external_int_get_vx(msg); global_position_setpoint_external_int->vy = mavlink_msg_global_position_setpoint_external_int_get_vy(msg); global_position_setpoint_external_int->vz = mavlink_msg_global_position_setpoint_external_int_get_vz(msg); - global_position_setpoint_external_int->ax = mavlink_msg_global_position_setpoint_external_int_get_ax(msg); - global_position_setpoint_external_int->ay = mavlink_msg_global_position_setpoint_external_int_get_ay(msg); - global_position_setpoint_external_int->az = mavlink_msg_global_position_setpoint_external_int_get_az(msg); - global_position_setpoint_external_int->ignore_mask = mavlink_msg_global_position_setpoint_external_int_get_ignore_mask(msg); + global_position_setpoint_external_int->afx = mavlink_msg_global_position_setpoint_external_int_get_afx(msg); + global_position_setpoint_external_int->afy = mavlink_msg_global_position_setpoint_external_int_get_afy(msg); + global_position_setpoint_external_int->afz = mavlink_msg_global_position_setpoint_external_int_get_afz(msg); + global_position_setpoint_external_int->type_mask = mavlink_msg_global_position_setpoint_external_int_get_type_mask(msg); global_position_setpoint_external_int->target_system = mavlink_msg_global_position_setpoint_external_int_get_target_system(msg); global_position_setpoint_external_int->target_component = mavlink_msg_global_position_setpoint_external_int_get_target_component(msg); #else diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h index b184e7c9c..84f15bf63 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_raw.h @@ -13,7 +13,7 @@ typedef struct __mavlink_gps2_raw_t uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255 uint8_t dgps_numch; ///< Number of DGPS satellites } mavlink_gps2_raw_t; @@ -52,7 +52,7 @@ typedef struct __mavlink_gps2_raw_t * @param msg The MAVLink message to compress the data into * * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. * @param lat Latitude (WGS84), in degrees * 1E7 * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) @@ -117,7 +117,7 @@ static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t comp * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. * @param lat Latitude (WGS84), in degrees * 1E7 * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) @@ -208,7 +208,7 @@ static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8 * @param chan MAVLink channel to send the message * * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. * @param lat Latitude (WGS84), in degrees * 1E7 * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) @@ -339,7 +339,7 @@ static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_ /** * @brief Get field fix_type from gps2_raw message * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK Fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */ static inline uint8_t mavlink_msg_gps2_raw_get_fix_type(const mavlink_message_t* msg) { diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h new file mode 100644 index 000000000..4c2d93c6e --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps2_rtk.h @@ -0,0 +1,497 @@ +// MESSAGE GPS2_RTK PACKING + +#define MAVLINK_MSG_ID_GPS2_RTK 128 + +typedef struct __mavlink_gps2_rtk_t +{ + uint32_t time_last_baseline_ms; ///< Time since boot of last baseline message received in ms. + uint32_t tow; ///< GPS Time of Week of last baseline + int32_t baseline_a_mm; ///< Current baseline in ECEF x or NED north component in mm. + int32_t baseline_b_mm; ///< Current baseline in ECEF y or NED east component in mm. + int32_t baseline_c_mm; ///< Current baseline in ECEF z or NED down component in mm. + uint32_t accuracy; ///< Current estimate of baseline accuracy. + int32_t iar_num_hypotheses; ///< Current number of integer ambiguity hypotheses. + uint16_t wn; ///< GPS Week Number of last baseline + uint8_t rtk_receiver_id; ///< Identification of connected RTK receiver. + uint8_t rtk_health; ///< GPS-specific health report for RTK data. + uint8_t rtk_rate; ///< Rate of baseline messages being received by GPS, in HZ + uint8_t nsats; ///< Current number of sats used for RTK calculation. + uint8_t baseline_coords_type; ///< Coordinate system of baseline. 0 == ECEF, 1 == NED +} mavlink_gps2_rtk_t; + +#define MAVLINK_MSG_ID_GPS2_RTK_LEN 35 +#define MAVLINK_MSG_ID_128_LEN 35 + +#define MAVLINK_MSG_ID_GPS2_RTK_CRC 226 +#define MAVLINK_MSG_ID_128_CRC 226 + + + +#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \ + "GPS2_RTK", \ + 13, \ + { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \ + { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \ + { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \ + { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \ + { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \ + { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \ + { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \ + } \ +} + + +/** + * @brief Pack a gps2_rtk message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#else + mavlink_gps2_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +} + +/** + * @brief Pack a gps2_rtk message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#else + mavlink_gps2_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS2_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +} + +/** + * @brief Encode a gps2_rtk struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps2_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) +{ + return mavlink_msg_gps2_rtk_pack(system_id, component_id, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); +} + +/** + * @brief Encode a gps2_rtk struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps2_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk) +{ + return mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, chan, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses); +} + +/** + * @brief Send a gps2_rtk message + * @param chan MAVLink channel to send the message + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps2_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#else + mavlink_gps2_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS2_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#else + mavlink_gps2_rtk_t *packet = (mavlink_gps2_rtk_t *)msgbuf; + packet->time_last_baseline_ms = time_last_baseline_ms; + packet->tow = tow; + packet->baseline_a_mm = baseline_a_mm; + packet->baseline_b_mm = baseline_b_mm; + packet->baseline_c_mm = baseline_c_mm; + packet->accuracy = accuracy; + packet->iar_num_hypotheses = iar_num_hypotheses; + packet->wn = wn; + packet->rtk_receiver_id = rtk_receiver_id; + packet->rtk_health = rtk_health; + packet->rtk_rate = rtk_rate; + packet->nsats = nsats; + packet->baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS2_RTK UNPACKING + + +/** + * @brief Get field time_last_baseline_ms from gps2_rtk message + * + * @return Time since boot of last baseline message received in ms. + */ +static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field rtk_receiver_id from gps2_rtk message + * + * @return Identification of connected RTK receiver. + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field wn from gps2_rtk message + * + * @return GPS Week Number of last baseline + */ +static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field tow from gps2_rtk message + * + * @return GPS Time of Week of last baseline + */ +static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field rtk_health from gps2_rtk message + * + * @return GPS-specific health report for RTK data. + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field rtk_rate from gps2_rtk message + * + * @return Rate of baseline messages being received by GPS, in HZ + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field nsats from gps2_rtk message + * + * @return Current number of sats used for RTK calculation. + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field baseline_coords_type from gps2_rtk message + * + * @return Coordinate system of baseline. 0 == ECEF, 1 == NED + */ +static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field baseline_a_mm from gps2_rtk message + * + * @return Current baseline in ECEF x or NED north component in mm. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field baseline_b_mm from gps2_rtk message + * + * @return Current baseline in ECEF y or NED east component in mm. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field baseline_c_mm from gps2_rtk message + * + * @return Current baseline in ECEF z or NED down component in mm. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field accuracy from gps2_rtk message + * + * @return Current estimate of baseline accuracy. + */ +static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field iar_num_hypotheses from gps2_rtk message + * + * @return Current number of integer ambiguity hypotheses. + */ +static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 24); +} + +/** + * @brief Decode a gps2_rtk message into a struct + * + * @param msg The message to decode + * @param gps2_rtk C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps2_rtk_decode(const mavlink_message_t* msg, mavlink_gps2_rtk_t* gps2_rtk) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps2_rtk->time_last_baseline_ms = mavlink_msg_gps2_rtk_get_time_last_baseline_ms(msg); + gps2_rtk->tow = mavlink_msg_gps2_rtk_get_tow(msg); + gps2_rtk->baseline_a_mm = mavlink_msg_gps2_rtk_get_baseline_a_mm(msg); + gps2_rtk->baseline_b_mm = mavlink_msg_gps2_rtk_get_baseline_b_mm(msg); + gps2_rtk->baseline_c_mm = mavlink_msg_gps2_rtk_get_baseline_c_mm(msg); + gps2_rtk->accuracy = mavlink_msg_gps2_rtk_get_accuracy(msg); + gps2_rtk->iar_num_hypotheses = mavlink_msg_gps2_rtk_get_iar_num_hypotheses(msg); + gps2_rtk->wn = mavlink_msg_gps2_rtk_get_wn(msg); + gps2_rtk->rtk_receiver_id = mavlink_msg_gps2_rtk_get_rtk_receiver_id(msg); + gps2_rtk->rtk_health = mavlink_msg_gps2_rtk_get_rtk_health(msg); + gps2_rtk->rtk_rate = mavlink_msg_gps2_rtk_get_rtk_rate(msg); + gps2_rtk->nsats = mavlink_msg_gps2_rtk_get_nsats(msg); + gps2_rtk->baseline_coords_type = mavlink_msg_gps2_rtk_get_baseline_coords_type(msg); +#else + memcpy(gps2_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RTK_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h index b53996206..9ab81fcfc 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h @@ -12,7 +12,7 @@ typedef struct __mavlink_gps_raw_int_t uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX - uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255 } mavlink_gps_raw_int_t; @@ -48,7 +48,7 @@ typedef struct __mavlink_gps_raw_int_t * @param msg The MAVLink message to compress the data into * * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. * @param lat Latitude (WGS84), in degrees * 1E7 * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) @@ -107,7 +107,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. * @param lat Latitude (WGS84), in degrees * 1E7 * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) @@ -192,7 +192,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, ui * @param chan MAVLink channel to send the message * * @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot) - * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. * @param lat Latitude (WGS84), in degrees * 1E7 * @param lon Longitude (WGS84), in degrees * 1E7 * @param alt Altitude (WGS84), in meters * 1000 (positive for up) @@ -313,7 +313,7 @@ static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_messa /** * @brief Get field fix_type from gps_raw_int message * - * @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. + * @return 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */ static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg) { diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_rtk.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_rtk.h new file mode 100644 index 000000000..31052ec25 --- /dev/null +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_gps_rtk.h @@ -0,0 +1,497 @@ +// MESSAGE GPS_RTK PACKING + +#define MAVLINK_MSG_ID_GPS_RTK 127 + +typedef struct __mavlink_gps_rtk_t +{ + uint32_t time_last_baseline_ms; ///< Time since boot of last baseline message received in ms. + uint32_t tow; ///< GPS Time of Week of last baseline + int32_t baseline_a_mm; ///< Current baseline in ECEF x or NED north component in mm. + int32_t baseline_b_mm; ///< Current baseline in ECEF y or NED east component in mm. + int32_t baseline_c_mm; ///< Current baseline in ECEF z or NED down component in mm. + uint32_t accuracy; ///< Current estimate of baseline accuracy. + int32_t iar_num_hypotheses; ///< Current number of integer ambiguity hypotheses. + uint16_t wn; ///< GPS Week Number of last baseline + uint8_t rtk_receiver_id; ///< Identification of connected RTK receiver. + uint8_t rtk_health; ///< GPS-specific health report for RTK data. + uint8_t rtk_rate; ///< Rate of baseline messages being received by GPS, in HZ + uint8_t nsats; ///< Current number of sats used for RTK calculation. + uint8_t baseline_coords_type; ///< Coordinate system of baseline. 0 == ECEF, 1 == NED +} mavlink_gps_rtk_t; + +#define MAVLINK_MSG_ID_GPS_RTK_LEN 35 +#define MAVLINK_MSG_ID_127_LEN 35 + +#define MAVLINK_MSG_ID_GPS_RTK_CRC 25 +#define MAVLINK_MSG_ID_127_CRC 25 + + + +#define MAVLINK_MESSAGE_INFO_GPS_RTK { \ + "GPS_RTK", \ + 13, \ + { { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \ + { "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \ + { "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \ + { "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \ + { "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \ + { "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \ + { "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \ + { "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \ + { "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \ + { "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \ + { "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \ + { "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \ + { "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \ + } \ +} + + +/** + * @brief Pack a gps_rtk message + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, + uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#else + mavlink_gps_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +} + +/** + * @brief Pack a gps_rtk message on a channel + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + * @return length of the message in bytes (excluding serial stream start sign) + */ +static inline uint16_t mavlink_msg_gps_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, + mavlink_message_t* msg, + uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#else + mavlink_gps_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + + memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif + + msg->msgid = MAVLINK_MSG_ID_GPS_RTK; +#if MAVLINK_CRC_EXTRA + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +} + +/** + * @brief Encode a gps_rtk struct + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param msg The MAVLink message to compress the data into + * @param gps_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) +{ + return mavlink_msg_gps_rtk_pack(system_id, component_id, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); +} + +/** + * @brief Encode a gps_rtk struct on a channel + * + * @param system_id ID of this system + * @param component_id ID of this component (e.g. 200 for IMU) + * @param chan The MAVLink channel this message will be sent over + * @param msg The MAVLink message to compress the data into + * @param gps_rtk C-struct to read the message contents from + */ +static inline uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk) +{ + return mavlink_msg_gps_rtk_pack_chan(system_id, component_id, chan, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses); +} + +/** + * @brief Send a gps_rtk message + * @param chan MAVLink channel to send the message + * + * @param time_last_baseline_ms Time since boot of last baseline message received in ms. + * @param rtk_receiver_id Identification of connected RTK receiver. + * @param wn GPS Week Number of last baseline + * @param tow GPS Time of Week of last baseline + * @param rtk_health GPS-specific health report for RTK data. + * @param rtk_rate Rate of baseline messages being received by GPS, in HZ + * @param nsats Current number of sats used for RTK calculation. + * @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED + * @param baseline_a_mm Current baseline in ECEF x or NED north component in mm. + * @param baseline_b_mm Current baseline in ECEF y or NED east component in mm. + * @param baseline_c_mm Current baseline in ECEF z or NED down component in mm. + * @param accuracy Current estimate of baseline accuracy. + * @param iar_num_hypotheses Current number of integer ambiguity hypotheses. + */ +#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS + +static inline void mavlink_msg_gps_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char buf[MAVLINK_MSG_ID_GPS_RTK_LEN]; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#else + mavlink_gps_rtk_t packet; + packet.time_last_baseline_ms = time_last_baseline_ms; + packet.tow = tow; + packet.baseline_a_mm = baseline_a_mm; + packet.baseline_b_mm = baseline_b_mm; + packet.baseline_c_mm = baseline_c_mm; + packet.accuracy = accuracy; + packet.iar_num_hypotheses = iar_num_hypotheses; + packet.wn = wn; + packet.rtk_receiver_id = rtk_receiver_id; + packet.rtk_health = rtk_health; + packet.rtk_rate = rtk_rate; + packet.nsats = nsats; + packet.baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#endif +} + +#if MAVLINK_MSG_ID_GPS_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN +/* + This varient of _send() can be used to save stack space by re-using + memory from the receive buffer. The caller provides a + mavlink_message_t which is the size of a full mavlink message. This + is usually the receive buffer for the channel, and allows a reply to an + incoming message with minimum stack space usage. + */ +static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses) +{ +#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS + char *buf = (char *)msgbuf; + _mav_put_uint32_t(buf, 0, time_last_baseline_ms); + _mav_put_uint32_t(buf, 4, tow); + _mav_put_int32_t(buf, 8, baseline_a_mm); + _mav_put_int32_t(buf, 12, baseline_b_mm); + _mav_put_int32_t(buf, 16, baseline_c_mm); + _mav_put_uint32_t(buf, 20, accuracy); + _mav_put_int32_t(buf, 24, iar_num_hypotheses); + _mav_put_uint16_t(buf, 28, wn); + _mav_put_uint8_t(buf, 30, rtk_receiver_id); + _mav_put_uint8_t(buf, 31, rtk_health); + _mav_put_uint8_t(buf, 32, rtk_rate); + _mav_put_uint8_t(buf, 33, nsats); + _mav_put_uint8_t(buf, 34, baseline_coords_type); + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#else + mavlink_gps_rtk_t *packet = (mavlink_gps_rtk_t *)msgbuf; + packet->time_last_baseline_ms = time_last_baseline_ms; + packet->tow = tow; + packet->baseline_a_mm = baseline_a_mm; + packet->baseline_b_mm = baseline_b_mm; + packet->baseline_c_mm = baseline_c_mm; + packet->accuracy = accuracy; + packet->iar_num_hypotheses = iar_num_hypotheses; + packet->wn = wn; + packet->rtk_receiver_id = rtk_receiver_id; + packet->rtk_health = rtk_health; + packet->rtk_rate = rtk_rate; + packet->nsats = nsats; + packet->baseline_coords_type = baseline_coords_type; + +#if MAVLINK_CRC_EXTRA + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC); +#else + _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +#endif +} +#endif + +#endif + +// MESSAGE GPS_RTK UNPACKING + + +/** + * @brief Get field time_last_baseline_ms from gps_rtk message + * + * @return Time since boot of last baseline message received in ms. + */ +static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 0); +} + +/** + * @brief Get field rtk_receiver_id from gps_rtk message + * + * @return Identification of connected RTK receiver. + */ +static inline uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 30); +} + +/** + * @brief Get field wn from gps_rtk message + * + * @return GPS Week Number of last baseline + */ +static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint16_t(msg, 28); +} + +/** + * @brief Get field tow from gps_rtk message + * + * @return GPS Time of Week of last baseline + */ +static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 4); +} + +/** + * @brief Get field rtk_health from gps_rtk message + * + * @return GPS-specific health report for RTK data. + */ +static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 31); +} + +/** + * @brief Get field rtk_rate from gps_rtk message + * + * @return Rate of baseline messages being received by GPS, in HZ + */ +static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 32); +} + +/** + * @brief Get field nsats from gps_rtk message + * + * @return Current number of sats used for RTK calculation. + */ +static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 33); +} + +/** + * @brief Get field baseline_coords_type from gps_rtk message + * + * @return Coordinate system of baseline. 0 == ECEF, 1 == NED + */ +static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint8_t(msg, 34); +} + +/** + * @brief Get field baseline_a_mm from gps_rtk message + * + * @return Current baseline in ECEF x or NED north component in mm. + */ +static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 8); +} + +/** + * @brief Get field baseline_b_mm from gps_rtk message + * + * @return Current baseline in ECEF y or NED east component in mm. + */ +static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 12); +} + +/** + * @brief Get field baseline_c_mm from gps_rtk message + * + * @return Current baseline in ECEF z or NED down component in mm. + */ +static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 16); +} + +/** + * @brief Get field accuracy from gps_rtk message + * + * @return Current estimate of baseline accuracy. + */ +static inline uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t* msg) +{ + return _MAV_RETURN_uint32_t(msg, 20); +} + +/** + * @brief Get field iar_num_hypotheses from gps_rtk message + * + * @return Current number of integer ambiguity hypotheses. + */ +static inline int32_t mavlink_msg_gps_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg) +{ + return _MAV_RETURN_int32_t(msg, 24); +} + +/** + * @brief Decode a gps_rtk message into a struct + * + * @param msg The message to decode + * @param gps_rtk C-struct to decode the message contents into + */ +static inline void mavlink_msg_gps_rtk_decode(const mavlink_message_t* msg, mavlink_gps_rtk_t* gps_rtk) +{ +#if MAVLINK_NEED_BYTE_SWAP + gps_rtk->time_last_baseline_ms = mavlink_msg_gps_rtk_get_time_last_baseline_ms(msg); + gps_rtk->tow = mavlink_msg_gps_rtk_get_tow(msg); + gps_rtk->baseline_a_mm = mavlink_msg_gps_rtk_get_baseline_a_mm(msg); + gps_rtk->baseline_b_mm = mavlink_msg_gps_rtk_get_baseline_b_mm(msg); + gps_rtk->baseline_c_mm = mavlink_msg_gps_rtk_get_baseline_c_mm(msg); + gps_rtk->accuracy = mavlink_msg_gps_rtk_get_accuracy(msg); + gps_rtk->iar_num_hypotheses = mavlink_msg_gps_rtk_get_iar_num_hypotheses(msg); + gps_rtk->wn = mavlink_msg_gps_rtk_get_wn(msg); + gps_rtk->rtk_receiver_id = mavlink_msg_gps_rtk_get_rtk_receiver_id(msg); + gps_rtk->rtk_health = mavlink_msg_gps_rtk_get_rtk_health(msg); + gps_rtk->rtk_rate = mavlink_msg_gps_rtk_get_rtk_rate(msg); + gps_rtk->nsats = mavlink_msg_gps_rtk_get_nsats(msg); + gps_rtk->baseline_coords_type = mavlink_msg_gps_rtk_get_baseline_coords_type(msg); +#else + memcpy(gps_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RTK_LEN); +#endif +} diff --git a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_ned_position_setpoint_external.h b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_ned_position_setpoint_external.h index 6e60578ce..b4f540275 100644 --- a/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_ned_position_setpoint_external.h +++ b/mavlink/include/mavlink/v1.0/common/mavlink_msg_local_ned_position_setpoint_external.h @@ -11,10 +11,10 @@ typedef struct __mavlink_local_ned_position_setpoint_external_t float vx; ///< X velocity in NED frame in meter / s float vy; ///< Y velocity in NED frame in meter / s float vz; ///< Z velocity in NED frame in meter / s - float ax; ///< X acceleration in NED frame in meter / s^2 - float ay; ///< Y acceleration in NED frame in meter / s^2 - float az; ///< Z acceleration in NED frame in meter / s^2 - uint16_t ignore_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint uint8_t target_system; ///< System ID uint8_t target_component; ///< Component ID uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 @@ -23,8 +23,8 @@ typedef struct __mavlink_local_ned_position_setpoint_external_t #define MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN 45 #define MAVLINK_MSG_ID_83_LEN 45 -#define MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC 121 -#define MAVLINK_MSG_ID_83_CRC 121 +#define MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_CRC 211 +#define MAVLINK_MSG_ID_83_CRC 211 @@ -38,10 +38,10 @@ typedef struct __mavlink_local_ned_position_setpoint_external_t { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_ned_position_setpoint_external_t, vx) }, \ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_ned_position_setpoint_external_t, vy) }, \ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_ned_position_setpoint_external_t, vz) }, \ - { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_ned_position_setpoint_external_t, ax) }, \ - { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_ned_position_setpoint_external_t, ay) }, \ - { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_ned_position_setpoint_external_t, az) }, \ - { "ignore_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_local_ned_position_setpoint_external_t, ignore_mask) }, \ + { "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_ned_position_setpoint_external_t, afx) }, \ + { "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_ned_position_setpoint_external_t, afy) }, \ + { "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_ned_position_setpoint_external_t, afz) }, \ + { "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_local_ned_position_setpoint_external_t, type_mask) }, \ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_local_ned_position_setpoint_external_t, target_system) }, \ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_local_ned_position_setpoint_external_t, target_component) }, \ { "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_local_ned_position_setpoint_external_t, coordinate_frame) }, \ @@ -59,20 +59,20 @@ typedef struct __mavlink_local_ned_position_setpoint_external_t * @param target_system System ID * @param target_component Component ID * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 - * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint * @param x X Position in NED frame in meters * @param y Y Position in NED frame in meters * @param z Z Position in NED frame in meters (note, altitude is negative in NED) * @param vx X velocity in NED frame in meter / s * @param vy Y velocity in NED frame in meter / s * @param vz Z velocity in NED frame in meter / s - * @param ax X acceleration in NED frame in meter / s^2 - * @param ay Y acceleration in NED frame in meter / s^2 - * @param az Z acceleration in NED frame in meter / s^2 + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t ignore_mask, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az) + uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN]; @@ -83,10 +83,10 @@ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack(uin _mav_put_float(buf, 16, vx); _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, ax); - _mav_put_float(buf, 32, ay); - _mav_put_float(buf, 36, az); - _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_uint16_t(buf, 40, type_mask); _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, target_component); _mav_put_uint8_t(buf, 44, coordinate_frame); @@ -101,10 +101,10 @@ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack(uin packet.vx = vx; packet.vy = vy; packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.ignore_mask = ignore_mask; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.type_mask = type_mask; packet.target_system = target_system; packet.target_component = target_component; packet.coordinate_frame = coordinate_frame; @@ -130,21 +130,21 @@ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack(uin * @param target_system System ID * @param target_component Component ID * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 - * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint * @param x X Position in NED frame in meters * @param y Y Position in NED frame in meters * @param z Z Position in NED frame in meters (note, altitude is negative in NED) * @param vx X velocity in NED frame in meter / s * @param vy Y velocity in NED frame in meter / s * @param vz Z velocity in NED frame in meter / s - * @param ax X acceleration in NED frame in meter / s^2 - * @param ay Y acceleration in NED frame in meter / s^2 - * @param az Z acceleration in NED frame in meter / s^2 + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, - uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t ignore_mask,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az) + uint32_t time_boot_ms,uint8_t target_system,uint8_t target_component,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN]; @@ -155,10 +155,10 @@ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack_cha _mav_put_float(buf, 16, vx); _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, ax); - _mav_put_float(buf, 32, ay); - _mav_put_float(buf, 36, az); - _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_uint16_t(buf, 40, type_mask); _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, target_component); _mav_put_uint8_t(buf, 44, coordinate_frame); @@ -173,10 +173,10 @@ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack_cha packet.vx = vx; packet.vy = vy; packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.ignore_mask = ignore_mask; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.type_mask = type_mask; packet.target_system = target_system; packet.target_component = target_component; packet.coordinate_frame = coordinate_frame; @@ -202,7 +202,7 @@ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_pack_cha */ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_ned_position_setpoint_external_t* local_ned_position_setpoint_external) { - return mavlink_msg_local_ned_position_setpoint_external_pack(system_id, component_id, msg, local_ned_position_setpoint_external->time_boot_ms, local_ned_position_setpoint_external->target_system, local_ned_position_setpoint_external->target_component, local_ned_position_setpoint_external->coordinate_frame, local_ned_position_setpoint_external->ignore_mask, local_ned_position_setpoint_external->x, local_ned_position_setpoint_external->y, local_ned_position_setpoint_external->z, local_ned_position_setpoint_external->vx, local_ned_position_setpoint_external->vy, local_ned_position_setpoint_external->vz, local_ned_position_setpoint_external->ax, local_ned_position_setpoint_external->ay, local_ned_position_setpoint_external->az); + return mavlink_msg_local_ned_position_setpoint_external_pack(system_id, component_id, msg, local_ned_position_setpoint_external->time_boot_ms, local_ned_position_setpoint_external->target_system, local_ned_position_setpoint_external->target_component, local_ned_position_setpoint_external->coordinate_frame, local_ned_position_setpoint_external->type_mask, local_ned_position_setpoint_external->x, local_ned_position_setpoint_external->y, local_ned_position_setpoint_external->z, local_ned_position_setpoint_external->vx, local_ned_position_setpoint_external->vy, local_ned_position_setpoint_external->vz, local_ned_position_setpoint_external->afx, local_ned_position_setpoint_external->afy, local_ned_position_setpoint_external->afz); } /** @@ -216,7 +216,7 @@ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_encode(u */ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_ned_position_setpoint_external_t* local_ned_position_setpoint_external) { - return mavlink_msg_local_ned_position_setpoint_external_pack_chan(system_id, component_id, chan, msg, local_ned_position_setpoint_external->time_boot_ms, local_ned_position_setpoint_external->target_system, local_ned_position_setpoint_external->target_component, local_ned_position_setpoint_external->coordinate_frame, local_ned_position_setpoint_external->ignore_mask, local_ned_position_setpoint_external->x, local_ned_position_setpoint_external->y, local_ned_position_setpoint_external->z, local_ned_position_setpoint_external->vx, local_ned_position_setpoint_external->vy, local_ned_position_setpoint_external->vz, local_ned_position_setpoint_external->ax, local_ned_position_setpoint_external->ay, local_ned_position_setpoint_external->az); + return mavlink_msg_local_ned_position_setpoint_external_pack_chan(system_id, component_id, chan, msg, local_ned_position_setpoint_external->time_boot_ms, local_ned_position_setpoint_external->target_system, local_ned_position_setpoint_external->target_component, local_ned_position_setpoint_external->coordinate_frame, local_ned_position_setpoint_external->type_mask, local_ned_position_setpoint_external->x, local_ned_position_setpoint_external->y, local_ned_position_setpoint_external->z, local_ned_position_setpoint_external->vx, local_ned_position_setpoint_external->vy, local_ned_position_setpoint_external->vz, local_ned_position_setpoint_external->afx, local_ned_position_setpoint_external->afy, local_ned_position_setpoint_external->afz); } /** @@ -227,20 +227,20 @@ static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_encode_c * @param target_system System ID * @param target_component Component ID * @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED, MAV_FRAME_LOCAL_OFFSET_NED = 5, MAV_FRAME_BODY_NED = 6, MAV_FRAME_BODY_OFFSET_NED = 7 - * @param ignore_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint * @param x X Position in NED frame in meters * @param y Y Position in NED frame in meters * @param z Z Position in NED frame in meters (note, altitude is negative in NED) * @param vx X velocity in NED frame in meter / s * @param vy Y velocity in NED frame in meter / s * @param vz Z velocity in NED frame in meter / s - * @param ax X acceleration in NED frame in meter / s^2 - * @param ay Y acceleration in NED frame in meter / s^2 - * @param az Z acceleration in NED frame in meter / s^2 + * @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N + * @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -static inline void mavlink_msg_local_ned_position_setpoint_external_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t ignore_mask, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az) +static inline void mavlink_msg_local_ned_position_setpoint_external_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_LOCAL_NED_POSITION_SETPOINT_EXTERNAL_LEN]; @@ -251,10 +251,10 @@ static inline void mavlink_msg_local_ned_position_setpoint_external_send(mavlink _mav_put_float(buf, 16, vx); _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, ax); - _mav_put_float(buf, 32, ay); - _mav_put_float(buf, 36, az); - _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_uint16_t(buf, 40, type_mask); _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, target_component); _mav_put_uint8_t(buf, 44, coordinate_frame); @@ -273,10 +273,10 @@ static inline void mavlink_msg_local_ned_position_setpoint_external_send(mavlink packet.vx = vx; packet.vy = vy; packet.vz = vz; - packet.ax = ax; - packet.ay = ay; - packet.az = az; - packet.ignore_mask = ignore_mask; + packet.afx = afx; + packet.afy = afy; + packet.afz = afz; + packet.type_mask = type_mask; packet.target_system = target_system; packet.target_component = target_component; packet.coordinate_frame = coordinate_frame; @@ -297,7 +297,7 @@ static inline void mavlink_msg_local_ned_position_setpoint_external_send(mavlink is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ -static inline void mavlink_msg_local_ned_position_setpoint_external_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t ignore_mask, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az) +static inline void mavlink_msg_local_ned_position_setpoint_external_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; @@ -308,10 +308,10 @@ static inline void mavlink_msg_local_ned_position_setpoint_external_send_buf(mav _mav_put_float(buf, 16, vx); _mav_put_float(buf, 20, vy); _mav_put_float(buf, 24, vz); - _mav_put_float(buf, 28, ax); - _mav_put_float(buf, 32, ay); - _mav_put_float(buf, 36, az); - _mav_put_uint16_t(buf, 40, ignore_mask); + _mav_put_float(buf, 28, afx); + _mav_put_float(buf, 32, afy); + _mav_put_float(buf, 36, afz); + _mav_put_uint16_t(buf, 40, type_mask); _mav_put_uint8_t(buf, 42, target_system); _mav_put_uint8_t(buf, 43, target_component); _mav_put_uint8_t(buf, 44, coordinate_frame); @@ -330,10 +330,10 @@ static inline void mavlink_msg_local_ned_position_setpoint_external_send_buf(mav packet->vx = vx; packet->vy = vy; packet->vz = vz; - packet->ax = ax; - packet->ay = ay; - packet->az = az; - packet->ignore_mask = ignore_mask; + packet->afx = afx; + packet->afy = afy; + packet->afz = afz; + packet->type_mask = type_mask; packet->target_system = target_system; packet->target_component = target_component; packet->coordinate_frame = coordinate_frame; @@ -393,11 +393,11 @@ static inline uint8_t mavlink_msg_local_ned_position_setpoint_external_get_coord } /** - * @brief Get field ignore_mask from local_ned_position_setpoint_external message + * @brief Get field type_mask from local_ned_position_setpoint_external message * - * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates it should follow the commanded attitude and rate and none of the setpoint dimensions should be ignored. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az + * @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint */ -static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_get_ignore_mask(const mavlink_message_t* msg) +static inline uint16_t mavlink_msg_local_ned_position_setpoint_external_get_type_mask(const mavlink_message_t* msg) { return _MAV_RETURN_uint16_t(msg, 40); } @@ -463,31 +463,31 @@ static inline float mavlink_msg_local_ned_position_setpoint_external_get_vz(cons } /** - * @brief Get field ax from local_ned_position_setpoint_external message + * @brief Get field afx from local_ned_position_setpoint_external message * - * @return X acceleration in NED frame in meter / s^2 + * @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ -static inline float mavlink_msg_local_ned_position_setpoint_external_get_ax(const mavlink_message_t* msg) +static inline float mavlink_msg_local_ned_position_setpoint_external_get_afx(const mavlink_message_t* msg) { return _MAV_RETURN_float(msg, 28); } /** - * @brief Get field ay from local_ned_position_setpoint_external message + * @brief Get field afy from local_ned_position_setpoint_external message * - * @return Y acceleration in NED frame in meter / s^2 + * @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ -static inline float mavlink_msg_local_ned_position_setpoint_external_get_ay(const mavlink_message_t* msg) +static inline float mavlink_msg_local_ned_position_setpoint_external_get_afy(const mavlink_message_t* msg) { return _MAV_RETURN_float(msg, 32); } /** - * @brief Get field az from local_ned_position_setpoint_external message + * @brief Get field afz from local_ned_position_setpoint_external message * - * @return Z acceleration in NED frame in meter / s^2 + * @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N */ -static inline float mavlink_msg_local_ned_position_setpoint_external_get_az(const mavlink_message_t* msg) +static inline float mavlink_msg_local_ned_position_setpoint_external_get_afz(const mavlink_message_t* msg) { return _MAV_RETURN_float(msg, 36); } @@ -508,10 +508,10 @@ static inline void mavlink_msg_local_ned_position_setpoint_external_decode(const local_ned_position_setpoint_external->vx = mavlink_msg_local_ned_position_setpoint_external_get_vx(msg); local_ned_position_setpoint_external->vy = mavlink_msg_local_ned_position_setpoint_external_get_vy(msg); local_ned_position_setpoint_external->vz = mavlink_msg_local_ned_position_setpoint_external_get_vz(msg); - local_ned_position_setpoint_external->ax = mavlink_msg_local_ned_position_setpoint_external_get_ax(msg); - local_ned_position_setpoint_external->ay = mavlink_msg_local_ned_position_setpoint_external_get_ay(msg); - local_ned_position_setpoint_external->az = mavlink_msg_local_ned_position_setpoint_external_get_az(msg); - local_ned_position_setpoint_external->ignore_mask = mavlink_msg_local_ned_position_setpoint_external_get_ignore_mask(msg); + local_ned_position_setpoint_external->afx = mavlink_msg_local_ned_position_setpoint_external_get_afx(msg); + local_ned_position_setpoint_external->afy = mavlink_msg_local_ned_position_setpoint_external_get_afy(msg); + local_ned_position_setpoint_external->afz = mavlink_msg_local_ned_position_setpoint_external_get_afz(msg); + local_ned_position_setpoint_external->type_mask = mavlink_msg_local_ned_position_setpoint_external_get_type_mask(msg); local_ned_position_setpoint_external->target_system = mavlink_msg_local_ned_position_setpoint_external_get_target_system(msg); local_ned_position_setpoint_external->target_component = mavlink_msg_local_ned_position_setpoint_external_get_target_component(msg); local_ned_position_setpoint_external->coordinate_frame = mavlink_msg_local_ned_position_setpoint_external_get_coordinate_frame(msg); diff --git a/mavlink/include/mavlink/v1.0/common/testsuite.h b/mavlink/include/mavlink/v1.0/common/testsuite.h index ccfe74f08..73712781c 100644 --- a/mavlink/include/mavlink/v1.0/common/testsuite.h +++ b/mavlink/include/mavlink/v1.0/common/testsuite.h @@ -3456,10 +3456,10 @@ static void mavlink_test_local_ned_position_setpoint_external(uint8_t system_id, packet1.vx = packet_in.vx; packet1.vy = packet_in.vy; packet1.vz = packet_in.vz; - packet1.ax = packet_in.ax; - packet1.ay = packet_in.ay; - packet1.az = packet_in.az; - packet1.ignore_mask = packet_in.ignore_mask; + packet1.afx = packet_in.afx; + packet1.afy = packet_in.afy; + packet1.afz = packet_in.afz; + packet1.type_mask = packet_in.type_mask; packet1.target_system = packet_in.target_system; packet1.target_component = packet_in.target_component; packet1.coordinate_frame = packet_in.coordinate_frame; @@ -3472,12 +3472,12 @@ static void mavlink_test_local_ned_position_setpoint_external(uint8_t system_id, MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_ned_position_setpoint_external_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.ignore_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az ); + mavlink_msg_local_ned_position_setpoint_external_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz ); mavlink_msg_local_ned_position_setpoint_external_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_ned_position_setpoint_external_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.ignore_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az ); + mavlink_msg_local_ned_position_setpoint_external_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz ); mavlink_msg_local_ned_position_setpoint_external_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -3490,7 +3490,7 @@ static void mavlink_test_local_ned_position_setpoint_external(uint8_t system_id, MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_local_ned_position_setpoint_external_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.ignore_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az ); + mavlink_msg_local_ned_position_setpoint_external_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.type_mask , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz ); mavlink_msg_local_ned_position_setpoint_external_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } @@ -3524,10 +3524,10 @@ static void mavlink_test_global_position_setpoint_external_int(uint8_t system_id packet1.vx = packet_in.vx; packet1.vy = packet_in.vy; packet1.vz = packet_in.vz; - packet1.ax = packet_in.ax; - packet1.ay = packet_in.ay; - packet1.az = packet_in.az; - packet1.ignore_mask = packet_in.ignore_mask; + packet1.afx = packet_in.afx; + packet1.afy = packet_in.afy; + packet1.afz = packet_in.afz; + packet1.type_mask = packet_in.type_mask; packet1.target_system = packet_in.target_system; packet1.target_component = packet_in.target_component; @@ -3539,12 +3539,12 @@ static void mavlink_test_global_position_setpoint_external_int(uint8_t system_id MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_setpoint_external_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.ignore_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az ); + mavlink_msg_global_position_setpoint_external_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz ); mavlink_msg_global_position_setpoint_external_int_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_setpoint_external_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.ignore_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az ); + mavlink_msg_global_position_setpoint_external_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz ); mavlink_msg_global_position_setpoint_external_int_decode(&msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); @@ -3557,7 +3557,7 @@ static void mavlink_test_global_position_setpoint_external_int(uint8_t system_id MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_global_position_setpoint_external_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.ignore_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.ax , packet1.ay , packet1.az ); + mavlink_msg_global_position_setpoint_external_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.target_system , packet1.target_component , packet1.type_mask , packet1.lat_int , packet1.lon_int , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.afx , packet1.afy , packet1.afz ); mavlink_msg_global_position_setpoint_external_int_decode(last_msg, &packet2); MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } @@ -5331,6 +5331,140 @@ static void mavlink_test_serial_control(uint8_t system_id, uint8_t component_id, MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); } +static void mavlink_test_gps_rtk(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) +{ + mavlink_message_t msg; + uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; + uint16_t i; + mavlink_gps_rtk_t packet_in = { + 963497464, + }963497672, + }963497880, + }963498088, + }963498296, + }963498504, + }963498712, + }18691, + }223, + }34, + }101, + }168, + }235, + }; + mavlink_gps_rtk_t packet1, packet2; + memset(&packet1, 0, sizeof(packet1)); + packet1.time_last_baseline_ms = packet_in.time_last_baseline_ms; + packet1.tow = packet_in.tow; + packet1.baseline_a_mm = packet_in.baseline_a_mm; + packet1.baseline_b_mm = packet_in.baseline_b_mm; + packet1.baseline_c_mm = packet_in.baseline_c_mm; + packet1.accuracy = packet_in.accuracy; + packet1.iar_num_hypotheses = packet_in.iar_num_hypotheses; + packet1.wn = packet_in.wn; + packet1.rtk_receiver_id = packet_in.rtk_receiver_id; + packet1.rtk_health = packet_in.rtk_health; + packet1.rtk_rate = packet_in.rtk_rate; + packet1.nsats = packet_in.nsats; + packet1.baseline_coords_type = packet_in.baseline_coords_type; + + + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_gps_rtk_encode(system_id, component_id, &msg, &packet1); + mavlink_msg_gps_rtk_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_gps_rtk_pack(system_id, component_id, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); + mavlink_msg_gps_rtk_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_gps_rtk_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_last_baseline_ms , packet1.rtk_receiver_id , packet1.wn , packet1.tow , packet1.rtk_health , packet1.rtk_rate , packet1.nsats , packet1.baseline_coords_type , packet1.baseline_a_mm , packet1.baseline_b_mm , packet1.baseline_c_mm , packet1.accuracy , packet1.iar_num_hypotheses ); + mavlink_msg_gps_rtk_decode(&msg, &packet2); + MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); + + memset(&packet2, 0, sizeof(packet2)); + mavlink_msg_to_send_buffer(buffer, &msg); + for (i=0; i Date: Wed, 2 Jul 2014 16:45:42 +0200 Subject: Fix compile error: rename field in rc_channels.h --- src/modules/uORB/topics/rc_channels.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uORB/topics/rc_channels.h b/src/modules/uORB/topics/rc_channels.h index 829d8e57d..8978de471 100644 --- a/src/modules/uORB/topics/rc_channels.h +++ b/src/modules/uORB/topics/rc_channels.h @@ -56,7 +56,7 @@ enum RC_CHANNELS_FUNCTION { RETURN, POSCTL, LOITER, - OFFBOARD_MODE, + OFFBOARD, ACRO, FLAPS, AUX_1, -- cgit v1.2.3 From 6c6de9395818717916bbc1077fecd51c4db87936 Mon Sep 17 00:00:00 2001 From: Andrew Chambers Date: Wed, 2 Jul 2014 10:04:07 -0700 Subject: Fixed heading covariance calculation and build errors. --- src/modules/uavcan/gnss_receiver.cpp | 17 ++++++++++++----- src/modules/uavcan/module.mk | 3 ++- 2 files changed, 14 insertions(+), 6 deletions(-) diff --git a/src/modules/uavcan/gnss_receiver.cpp b/src/modules/uavcan/gnss_receiver.cpp index e92468333..490e35bd1 100644 --- a/src/modules/uavcan/gnss_receiver.cpp +++ b/src/modules/uavcan/gnss_receiver.cpp @@ -80,17 +80,24 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure Date: Wed, 2 Jul 2014 11:18:30 -0700 Subject: Fixed bug with zero-sized covariance arrays --- src/modules/uavcan/gnss_receiver.cpp | 77 +++++++++++++++++++++++------------- src/modules/uavcan/uavcan_main.cpp | 23 +++++------ 2 files changed, 61 insertions(+), 39 deletions(-) diff --git a/src/modules/uavcan/gnss_receiver.cpp b/src/modules/uavcan/gnss_receiver.cpp index 490e35bd1..23c221565 100644 --- a/src/modules/uavcan/gnss_receiver.cpp +++ b/src/modules/uavcan/gnss_receiver.cpp @@ -42,12 +42,13 @@ #include "gnss_receiver.hpp" #include -#define MM_PER_CM 10 // Millimeters per centimeter +#define MM_PER_CM 10 // Millimeters per centimeter +#define EXPECTED_COV_SIZE 9 // Expect a 3x3 matrix for position and velocity covariance UavcanGnssReceiver::UavcanGnssReceiver(uavcan::INode &node) : - _node(node), - _uavcan_sub_status(node), - _report_pub(-1) +_node(node), +_uavcan_sub_status(node), +_report_pub(-1) { } @@ -77,32 +78,52 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure 0); + bool valid_velocity_covariance = (msg.velocity_covariance.size() == EXPECTED_COV_SIZE && + msg.velocity_covariance[0] > 0); + + if (valid_position_covariance) { + _report.p_variance_m = msg.position_covariance[0] + msg.position_covariance[4]; + _report.eph_m = sqrtf(_report.p_variance_m); + } else { + _report.p_variance_m = -1.0; + _report.eph_m = -1.0; + } + + if (valid_velocity_covariance) { + _report.s_variance_m_s = msg.velocity_covariance[0] + msg.velocity_covariance[4] + msg.velocity_covariance[8]; + + /* There is a nonlinear relationship between the velocity vector and the heading. + * Use Jacobian to transform velocity covariance to heading covariance + * + * Nonlinear equation: + * heading = atan2(vel_e_m_s, vel_n_m_s) + * For math, see http://en.wikipedia.org/wiki/Atan2#Derivative + * + * To calculate the variance of heading from the variance of velocity, + * cov(heading) = J(velocity)*cov(velocity)*J(velocity)^T + */ + float vel_n = msg.ned_velocity[0]; + float vel_e = msg.ned_velocity[1]; + float vel_n_sq = vel_n * vel_n; + float vel_e_sq = vel_e * vel_e; + _report.c_variance_rad = + (vel_e_sq * msg.velocity_covariance[0] + + -2 * vel_n * vel_e * msg.velocity_covariance[1] + // Covariance matrix is symmetric + vel_n_sq* msg.velocity_covariance[4]) / ((vel_n_sq + vel_e_sq) * (vel_n_sq + vel_e_sq)); + + _report.epv_m = sqrtf(msg.position_covariance[8]); - _report.eph_m = sqrtf(_report.p_variance_m); - _report.epv_m = sqrtf(msg.position_covariance[8]); + } else { + _report.s_variance_m_s = -1.0; + _report.c_variance_rad = -1.0; + _report.epv_m = -1.0; + } + + _report.fix_type = msg.status; _report.timestamp_velocity = _report.timestamp_position; _report.vel_n_m_s = msg.ned_velocity[0]; diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 5bc437670..c0c07be53 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -243,21 +243,22 @@ int UavcanNode::run() _node.setStatusOk(); + /* + * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error). + * Please note that with such multiplexing it is no longer possible to rely only on + * the value returned from poll() to detect whether actuator control has timed out or not. + * Instead, all ORB events need to be checked individually (see below). + */ + _poll_fds[_poll_fds_num] = ::pollfd(); + _poll_fds[_poll_fds_num].fd = busevent_fd; + _poll_fds[_poll_fds_num].events = POLLIN; + _poll_fds_num += 1; + while (!_task_should_exit) { if (_groups_subscribed != _groups_required) { subscribe(); _groups_subscribed = _groups_required; - /* - * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error). - * Please note that with such multiplexing it is no longer possible to rely only on - * the value returned from poll() to detect whether actuator control has timed out or not. - * Instead, all ORB events need to be checked individually (see below). - */ - _poll_fds[_poll_fds_num] = ::pollfd(); - _poll_fds[_poll_fds_num].fd = busevent_fd; - _poll_fds[_poll_fds_num].events = POLLIN; - _poll_fds_num += 1; } const int poll_ret = ::poll(_poll_fds, _poll_fds_num, PollTimeoutMs); @@ -271,7 +272,7 @@ int UavcanNode::run() } else { // get controls for required topics bool controls_updated = false; - unsigned poll_id = 0; + unsigned poll_id = 1; for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { if (_poll_fds[poll_id].revents & POLLIN) { -- cgit v1.2.3 From 607b6511a413b5bc2b2b0ae350a9451e83da9803 Mon Sep 17 00:00:00 2001 From: Andrew Chambers Date: Wed, 2 Jul 2014 11:27:49 -0700 Subject: Fixed comments --- src/modules/uavcan/gnss_receiver.hpp | 6 ++---- src/modules/uavcan/uavcan_main.hpp | 2 +- 2 files changed, 3 insertions(+), 5 deletions(-) diff --git a/src/modules/uavcan/gnss_receiver.hpp b/src/modules/uavcan/gnss_receiver.hpp index abb8a821a..18df8da2f 100644 --- a/src/modules/uavcan/gnss_receiver.hpp +++ b/src/modules/uavcan/gnss_receiver.hpp @@ -34,10 +34,8 @@ /** * @file gnss_receiver.hpp * - * UAVCAN <--> ORB bridge for ESC messages: - * uavcan.equipment.esc.RawCommand - * uavcan.equipment.esc.RPMCommand - * uavcan.equipment.esc.Status + * UAVCAN --> ORB bridge for GNSS messages: + * uavcan.equipment.gnss.Fix * * @author Pavel Kirienko * @author Andrew Chambers diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 126d44137..443525379 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -109,7 +109,7 @@ private: static UavcanNode *_instance; ///< singleton pointer Node _node; ///< library instance UavcanEscController _esc_controller; - UavcanGnssReceiver _gnss_receiver; + UavcanGnssReceiver _gnss_receiver; MixerGroup *_mixers = nullptr; -- cgit v1.2.3 From 76aa871a7125c98e79db4dde42de7863a24a762c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 3 Jul 2014 00:26:33 +0200 Subject: estimator: Fixed body / world matrix initialization and reset --- src/modules/ekf_att_pos_estimator/estimator_23states.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index 9622f7e40..deaaf55fe 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -2503,12 +2503,12 @@ void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination) // Calculate initial Tbn matrix and rotate Mag measurements into NED // to set initial NED magnetic field states - Mat3f DCM; - quat2Tbn(DCM, initQuat); + quat2Tbn(Tbn, initQuat); + Tnb = Tbn.transpose(); Vector3f initMagNED; - initMagNED.x = DCM.x.x*initMagXYZ.x + DCM.x.y*initMagXYZ.y + DCM.x.z*initMagXYZ.z; - initMagNED.y = DCM.y.x*initMagXYZ.x + DCM.y.y*initMagXYZ.y + DCM.y.z*initMagXYZ.z; - initMagNED.z = DCM.z.x*initMagXYZ.x + DCM.z.y*initMagXYZ.y + DCM.z.z*initMagXYZ.z; + initMagNED.x = Tbn.x.x*initMagXYZ.x + Tbn.x.y*initMagXYZ.y + Tbn.x.z*initMagXYZ.z; + initMagNED.y = Tbn.y.x*initMagXYZ.x + Tbn.y.y*initMagXYZ.y + Tbn.y.z*initMagXYZ.z; + initMagNED.z = Tbn.z.x*initMagXYZ.x + Tbn.z.y*initMagXYZ.y + Tbn.z.z*initMagXYZ.z; magstate.q0 = initQuat[0]; magstate.q1 = initQuat[1]; @@ -2521,7 +2521,7 @@ void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination) magstate.magYbias = magBias.y; magstate.magZbias = magBias.z; magstate.R_MAG = sq(magMeasurementSigma); - magstate.DCM = DCM; + magstate.DCM = Tbn; // write to state vector for (uint8_t j=0; j<=3; j++) states[j] = initQuat[j]; // quaternions -- cgit v1.2.3 From 6c5e3d53412fa1cdad687818328b3bfc1a83e9ca Mon Sep 17 00:00:00 2001 From: Andrew Chambers Date: Wed, 2 Jul 2014 19:06:30 -0700 Subject: Address Paval's comments regarding extracting matrix from uavcan msg, position covariance calculation, and _poll_fds_num --- src/modules/uavcan/gnss_receiver.cpp | 28 +++++++++++++++------------- src/modules/uavcan/uavcan_main.cpp | 23 +++++++++++------------ 2 files changed, 26 insertions(+), 25 deletions(-) diff --git a/src/modules/uavcan/gnss_receiver.cpp b/src/modules/uavcan/gnss_receiver.cpp index 23c221565..65a7b4a2a 100644 --- a/src/modules/uavcan/gnss_receiver.cpp +++ b/src/modules/uavcan/gnss_receiver.cpp @@ -43,7 +43,6 @@ #include #define MM_PER_CM 10 // Millimeters per centimeter -#define EXPECTED_COV_SIZE 9 // Expect a 3x3 matrix for position and velocity covariance UavcanGnssReceiver::UavcanGnssReceiver(uavcan::INode &node) : _node(node), @@ -75,18 +74,19 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure 0); - bool valid_velocity_covariance = (msg.velocity_covariance.size() == EXPECTED_COV_SIZE && - msg.velocity_covariance[0] > 0); + + // Check if the msg contains valid covariance information + const bool valid_position_covariance = !msg.position_covariance.empty(); + const bool valid_velocity_covariance = !msg.velocity_covariance.empty(); if (valid_position_covariance) { - _report.p_variance_m = msg.position_covariance[0] + msg.position_covariance[4]; + float pos_cov[9]; + msg.position_covariance.unpackSquareMatrix(pos_cov); + _report.p_variance_m = std::max(pos_cov[0], pos_cov[4]); _report.eph_m = sqrtf(_report.p_variance_m); } else { _report.p_variance_m = -1.0; @@ -94,7 +94,9 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure 0) { orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index c0c07be53..5bc437670 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -243,22 +243,21 @@ int UavcanNode::run() _node.setStatusOk(); - /* - * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error). - * Please note that with such multiplexing it is no longer possible to rely only on - * the value returned from poll() to detect whether actuator control has timed out or not. - * Instead, all ORB events need to be checked individually (see below). - */ - _poll_fds[_poll_fds_num] = ::pollfd(); - _poll_fds[_poll_fds_num].fd = busevent_fd; - _poll_fds[_poll_fds_num].events = POLLIN; - _poll_fds_num += 1; - while (!_task_should_exit) { if (_groups_subscribed != _groups_required) { subscribe(); _groups_subscribed = _groups_required; + /* + * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error). + * Please note that with such multiplexing it is no longer possible to rely only on + * the value returned from poll() to detect whether actuator control has timed out or not. + * Instead, all ORB events need to be checked individually (see below). + */ + _poll_fds[_poll_fds_num] = ::pollfd(); + _poll_fds[_poll_fds_num].fd = busevent_fd; + _poll_fds[_poll_fds_num].events = POLLIN; + _poll_fds_num += 1; } const int poll_ret = ::poll(_poll_fds, _poll_fds_num, PollTimeoutMs); @@ -272,7 +271,7 @@ int UavcanNode::run() } else { // get controls for required topics bool controls_updated = false; - unsigned poll_id = 1; + unsigned poll_id = 0; for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { if (_poll_fds[poll_id].revents & POLLIN) { -- cgit v1.2.3 From 23164228c84f304326026c9fbda6822f2e99e9b3 Mon Sep 17 00:00:00 2001 From: Kynos Date: Thu, 3 Jul 2014 11:11:40 +0200 Subject: Added NAV-TIMEUTC valid flag defines --- src/drivers/gps/ubx.h | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index 1a9e7cb0c..65f2dd2ba 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -104,6 +104,13 @@ #define UBX_RX_NAV_PVT_FLAGS_PSMSTATE 0x1C /**< psmState (Power Save Mode state (see Power Management)) */ #define UBX_RX_NAV_PVT_FLAGS_HEADVEHVALID 0x20 /**< headVehValid (Heading of vehicle is valid) */ +/* RX NAV-TIMEUTC message content details */ +/* Bitfield "valid" masks */ +#define UBX_RX_NAV_TIMEUTC_VALID_VALIDTOW 0x01 /**< validTOW (1 = Valid Time of Week) */ +#define UBX_RX_NAV_TIMEUTC_VALID_VALIDKWN 0x02 /**< validWKN (1 = Valid Week Number) */ +#define UBX_RX_NAV_TIMEUTC_VALID_VALIDUTC 0x04 /**< validUTC (1 = Valid UTC Time) */ +#define UBX_RX_NAV_TIMEUTC_VALID_UTCSTANDARD 0xF0 /**< utcStandard (0..15 = UTC standard identifier) */ + /* TX CFG-PRT message contents */ #define UBX_TX_CFG_PRT_PORTID 0x01 /**< UART1 */ #define UBX_TX_CFG_PRT_MODE 0x000008D0 /**< 0b0000100011010000: 8N1 */ @@ -185,7 +192,7 @@ typedef struct { uint8_t hour; /**< Hour of day, range 0..23 (UTC) */ uint8_t min; /**< Minute of hour, range 0..59 (UTC) */ uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */ - uint8_t valid; /**< Validity flags (see UBX_RX_NAV_PVT_VALID_...) */ + uint8_t valid; /**< Validity flags (see UBX_RX_NAV_PVT_VALID_...) */ uint32_t tAcc; /**< Time accuracy estimate (UTC) [ns] */ int32_t nano; /**< Fraction of second (UTC) [-1e9...1e9 ns] */ uint8_t fixType; /**< GNSSfix type: 0 = No fix, 1 = Dead Reckoning only, 2 = 2D fix, 3 = 3d-fix, 4 = GNSS + dead reckoning, 5 = time only fix */ @@ -223,7 +230,7 @@ typedef struct { uint8_t hour; /**< Hour of day, range 0..23 (UTC) */ uint8_t min; /**< Minute of hour, range 0..59 (UTC) */ uint8_t sec; /**< Seconds of minute, range 0..60 (UTC) */ - uint8_t valid; /**< Validity Flags (see ubx documentation) */ + uint8_t valid; /**< Validity Flags (see UBX_RX_NAV_TIMEUTC_VALID_...) */ } ubx_payload_rx_nav_timeutc_t; /* Rx NAV-SVINFO Part 1 */ -- cgit v1.2.3 From 05be2400cb8d38645b86900edde38cbced0d22b4 Mon Sep 17 00:00:00 2001 From: Alexey Luchko Date: Thu, 3 Jul 2014 12:13:56 +0300 Subject: fix misprint `lowvsyslog` --- src/modules/systemlib/err.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/systemlib/err.c b/src/modules/systemlib/err.c index 6c0e876d1..998b5ac7d 100644 --- a/src/modules/systemlib/err.c +++ b/src/modules/systemlib/err.c @@ -86,7 +86,7 @@ warnerr_core(int errcode, const char *fmt, va_list args) fprintf(stderr, "\n"); #elif CONFIG_ARCH_LOWPUTC lowsyslog("%s: ", getprogname()); - lowvyslog(fmt, args); + lowvsyslog(fmt, args); /* convenience as many parts of NuttX use negative errno */ if (errcode < 0) -- cgit v1.2.3 From 7be2e0f13605eb9bb34eb04745a0e7a3936d94e9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 3 Jul 2014 11:18:00 +0200 Subject: Hotfix: Typo in disabled code path --- src/modules/systemlib/err.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/systemlib/err.c b/src/modules/systemlib/err.c index 6c0e876d1..60dcc62e0 100644 --- a/src/modules/systemlib/err.c +++ b/src/modules/systemlib/err.c @@ -86,7 +86,7 @@ warnerr_core(int errcode, const char *fmt, va_list args) fprintf(stderr, "\n"); #elif CONFIG_ARCH_LOWPUTC lowsyslog("%s: ", getprogname()); - lowvyslog(fmt, args); + lowsyslog(fmt, args); /* convenience as many parts of NuttX use negative errno */ if (errcode < 0) -- cgit v1.2.3 From 04cca73baac0b027451a76d50b1f3b365b1feeef Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 3 Jul 2014 11:26:26 +0200 Subject: Hotfix of the Hotfix 8) --- src/modules/systemlib/err.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/systemlib/err.c b/src/modules/systemlib/err.c index 60dcc62e0..998b5ac7d 100644 --- a/src/modules/systemlib/err.c +++ b/src/modules/systemlib/err.c @@ -86,7 +86,7 @@ warnerr_core(int errcode, const char *fmt, va_list args) fprintf(stderr, "\n"); #elif CONFIG_ARCH_LOWPUTC lowsyslog("%s: ", getprogname()); - lowsyslog(fmt, args); + lowvsyslog(fmt, args); /* convenience as many parts of NuttX use negative errno */ if (errcode < 0) -- cgit v1.2.3 From d5793d6cbee59779c1f5375fa3276bd0fddbe25e Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 3 Jul 2014 12:35:38 +0200 Subject: hk micro pcb quad: change min pwm value --- ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb index 42ec150c1..369aa1eb4 100644 --- a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb +++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb @@ -2,8 +2,9 @@ # # Hobbyking Micro Integrated PCB Quadcopter # -# Anton Babushkin +# Thomas Gubler # +echo "HK Micro PCB Quad" sh /etc/init.d/4001_quad_x @@ -23,5 +24,5 @@ then param set MC_YAWRATE_D 0.0 fi -set PWM_MIN 1100 +set PWM_MIN 1200 set PWM_DISARMED 900 -- cgit v1.2.3 From 2ec635dd1c33ef453818bd9396e3cec42694a30f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 3 Jul 2014 13:30:20 +0200 Subject: Update estimator --- .../ekf_att_pos_estimator/estimator_23states.cpp | 32 +++++++++++----------- .../ekf_att_pos_estimator/estimator_utilities.cpp | 1 + 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index 393cf4c5a..973de1382 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -1747,7 +1747,7 @@ void AttPosEKF::FuseOptFlow() static float losPred[2]; // Transformation matrix from nav to body axes - Mat3f Tnb; + Mat3f Tnb_local; // Transformation matrix from body to sensor axes // assume camera is aligned with Z body axis plus a misalignment // defined by 3 small angles about X, Y and Z body axis @@ -1764,7 +1764,7 @@ void AttPosEKF::FuseOptFlow() for (uint8_t i = 0; i < n_states; i++) { H_LOS[i] = 0.0f; } - Vector3f velNED; + Vector3f velNED_local; Vector3f relVelSensor; // Perform sequential fusion of optical flow measurements only when in the air and tilt is less than 30 deg. @@ -1786,9 +1786,9 @@ void AttPosEKF::FuseOptFlow() vd = statesAtOptFlowTime[6]; pd = statesAtOptFlowTime[9]; ptd = statesAtOptFlowTime[22]; - velNED.x = vn; - velNED.y = ve; - velNED.z = vd; + velNED_local.x = vn; + velNED_local.y = ve; + velNED_local.z = vd; // calculate rotation from NED to body axes float q00 = sq(q0); @@ -1801,24 +1801,24 @@ void AttPosEKF::FuseOptFlow() float q12 = q1 * q2; float q13 = q1 * q3; float q23 = q2 * q3; - Tnb.x.x = q00 + q11 - q22 - q33; - Tnb.y.y = q00 - q11 + q22 - q33; - Tnb.z.z = q00 - q11 - q22 + q33; - Tnb.y.x = 2*(q12 - q03); - Tnb.z.x = 2*(q13 + q02); - Tnb.x.y = 2*(q12 + q03); - Tnb.z.y = 2*(q23 - q01); - Tnb.x.z = 2*(q13 - q02); - Tnb.y.z = 2*(q23 + q01); + Tnb_local.x.x = q00 + q11 - q22 - q33; + Tnb_local.y.y = q00 - q11 + q22 - q33; + Tnb_local.z.z = q00 - q11 - q22 + q33; + Tnb_local.y.x = 2*(q12 - q03); + Tnb_local.z.x = 2*(q13 + q02); + Tnb_local.x.y = 2*(q12 + q03); + Tnb_local.z.y = 2*(q23 - q01); + Tnb_local.x.z = 2*(q13 - q02); + Tnb_local.y.z = 2*(q23 + q01); // calculate transformation from NED to sensor axes - Tns = Tbs*Tnb; + Tns = Tbs*Tnb_local; // calculate range from ground plain to centre of sensor fov assuming flat earth float range = ConstrainFloat(((ptd - pd)/Tns.z.z),0.5f,100.0f); // calculate relative velocity in sensor frame - relVelSensor = Tns*velNED; + relVelSensor = Tns*velNED_local; // calculate delta angles in sensor axes Vector3f delAngRel = Tbs*delAng; diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp index 24168b84c..29a8c8d1e 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp @@ -8,6 +8,7 @@ #ifdef EKF_DEBUG #include +#include static void ekf_debug_print(const char *fmt, va_list args) -- cgit v1.2.3 From 1cca3ca8a5469e66dbb5bebbe518b55e4af426d8 Mon Sep 17 00:00:00 2001 From: Kynos Date: Thu, 3 Jul 2014 13:33:29 +0200 Subject: Use NAV-PVT with ubx7 and ubx8 modules This replaces NAV-SOL, NAV-POSLLH, NAV-VELNED and NAV-TIMEUTC. --- src/drivers/gps/gps.cpp | 1 - src/drivers/gps/ubx.cpp | 125 +++++++++++++++++++++---- src/drivers/gps/ubx.h | 10 +- src/modules/mavlink/mavlink_receiver.cpp | 1 - src/modules/uORB/topics/vehicle_gps_position.h | 1 - 5 files changed, 113 insertions(+), 25 deletions(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 241e3bdf3..401b65dd4 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -299,7 +299,6 @@ GPS::task_main() _report_gps_pos.alt = (int32_t)1200e3f; _report_gps_pos.timestamp_variance = hrt_absolute_time(); _report_gps_pos.s_variance_m_s = 10.0f; - _report_gps_pos.p_variance_m = 10.0f; _report_gps_pos.c_variance_rad = 0.1f; _report_gps_pos.fix_type = 3; _report_gps_pos.eph = 0.9f; diff --git a/src/drivers/gps/ubx.cpp b/src/drivers/gps/ubx.cpp index 44434a1df..d0854f5e9 100644 --- a/src/drivers/gps/ubx.cpp +++ b/src/drivers/gps/ubx.cpp @@ -95,7 +95,8 @@ UBX::UBX(const int &fd, struct vehicle_gps_position_s *gps_position, struct sate _got_velned(false), _disable_cmd_last(0), _ack_waiting_msg(0), - _ubx_version(0) + _ubx_version(0), + _use_nav_pvt(false) { decode_init(); } @@ -190,38 +191,45 @@ UBX::configure(unsigned &baudrate) /* configure message rates */ /* the last argument is divisor for measurement rate (set by CFG RATE), i.e. 1 means 5Hz */ - configure_message_rate(UBX_MSG_NAV_POSLLH, 1); + /* try to set rate for NAV-PVT */ + /* (implemented for ubx7+ modules only, use NAV-SOL, NAV-POSLLH, NAV-VELNED and NAV-TIMEUTC for ubx6) */ + configure_message_rate(UBX_MSG_NAV_PVT, 1); if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { - return 1; - } - - configure_message_rate(UBX_MSG_NAV_TIMEUTC, 5); - - if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { - return 1; + _use_nav_pvt = false; + } else { + _use_nav_pvt = true; } + UBX_WARN("%susing NAV-PVT", _use_nav_pvt ? "" : "not "); - configure_message_rate(UBX_MSG_NAV_SOL, 1); + if (!_use_nav_pvt) { + configure_message_rate(UBX_MSG_NAV_TIMEUTC, 5); + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { + return 1; + } - if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { - return 1; - } + configure_message_rate(UBX_MSG_NAV_POSLLH, 1); + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { + return 1; + } - configure_message_rate(UBX_MSG_NAV_VELNED, 1); + configure_message_rate(UBX_MSG_NAV_SOL, 1); + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { + return 1; + } - if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { - return 1; + configure_message_rate(UBX_MSG_NAV_VELNED, 1); + if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { + return 1; + } } configure_message_rate(UBX_MSG_NAV_SVINFO, (_satellite_info != nullptr) ? 5 : 0); - if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { return 1; } configure_message_rate(UBX_MSG_MON_HW, 1); - if (wait_for_ack(UBX_MSG_CFG_MSG, UBX_CONFIG_TIMEOUT, true) < 0) { return 1; } @@ -454,11 +462,23 @@ UBX::payload_rx_init() _rx_state = UBX_RXMSG_HANDLE; // handle by default switch (_rx_msg) { + case UBX_MSG_NAV_PVT: + if ( (_rx_payload_length != UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7) /* u-blox 7 msg format */ + && (_rx_payload_length != UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8)) /* u-blox 8+ msg format */ + _rx_state = UBX_RXMSG_ERROR_LENGTH; + else if (!_configured) + _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + else if (!_use_nav_pvt) + _rx_state = UBX_RXMSG_DISABLE; // disable if not using NAV-PVT + break; + case UBX_MSG_NAV_POSLLH: if (_rx_payload_length != sizeof(ubx_payload_rx_nav_posllh_t)) _rx_state = UBX_RXMSG_ERROR_LENGTH; else if (!_configured) _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + else if (_use_nav_pvt) + _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead break; case UBX_MSG_NAV_SOL: @@ -466,6 +486,8 @@ UBX::payload_rx_init() _rx_state = UBX_RXMSG_ERROR_LENGTH; else if (!_configured) _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + else if (_use_nav_pvt) + _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead break; case UBX_MSG_NAV_TIMEUTC: @@ -473,6 +495,8 @@ UBX::payload_rx_init() _rx_state = UBX_RXMSG_ERROR_LENGTH; else if (!_configured) _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + else if (_use_nav_pvt) + _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead break; case UBX_MSG_NAV_SVINFO: @@ -489,6 +513,8 @@ UBX::payload_rx_init() _rx_state = UBX_RXMSG_ERROR_LENGTH; else if (!_configured) _rx_state = UBX_RXMSG_IGNORE; // ignore if not _configured + else if (_use_nav_pvt) + _rx_state = UBX_RXMSG_DISABLE; // disable if using NAV-PVT instead break; case UBX_MSG_MON_VER: @@ -675,6 +701,68 @@ UBX::payload_rx_done(void) // handle message switch (_rx_msg) { + case UBX_MSG_NAV_PVT: + UBX_TRACE_RXMSG("Rx NAV-PVT\n"); + + _gps_position->fix_type = _buf.payload_rx_nav_pvt.fixType; + _gps_position->satellites_used = _buf.payload_rx_nav_pvt.numSV; + + _gps_position->lat = _buf.payload_rx_nav_pvt.lat; + _gps_position->lon = _buf.payload_rx_nav_pvt.lon; + _gps_position->alt = _buf.payload_rx_nav_pvt.hMSL; + + _gps_position->eph = (float)_buf.payload_rx_nav_pvt.hAcc * 1e-3f; + _gps_position->epv = (float)_buf.payload_rx_nav_pvt.vAcc * 1e-3f; + _gps_position->s_variance_m_s = (float)_buf.payload_rx_nav_pvt.sAcc * 1e-3f; + + _gps_position->vel_m_s = (float)_buf.payload_rx_nav_pvt.gSpeed * 1e-3f; + + _gps_position->vel_n_m_s = (float)_buf.payload_rx_nav_pvt.velN * 1e-3f; + _gps_position->vel_e_m_s = (float)_buf.payload_rx_nav_pvt.velE * 1e-3f; + _gps_position->vel_d_m_s = (float)_buf.payload_rx_nav_pvt.velD * 1e-3f; + _gps_position->vel_ned_valid = true; + + _gps_position->cog_rad = (float)_buf.payload_rx_nav_pvt.headMot * M_DEG_TO_RAD_F * 1e-5f; + _gps_position->c_variance_rad = (float)_buf.payload_rx_nav_pvt.headAcc * M_DEG_TO_RAD_F * 1e-5f; + + { + /* convert to unix timestamp */ + struct tm timeinfo; + timeinfo.tm_year = _buf.payload_rx_nav_pvt.year - 1900; + timeinfo.tm_mon = _buf.payload_rx_nav_pvt.month - 1; + timeinfo.tm_mday = _buf.payload_rx_nav_pvt.day; + timeinfo.tm_hour = _buf.payload_rx_nav_pvt.hour; + timeinfo.tm_min = _buf.payload_rx_nav_pvt.min; + timeinfo.tm_sec = _buf.payload_rx_nav_pvt.sec; + time_t epoch = mktime(&timeinfo); + +#ifndef CONFIG_RTC + //Since we lack a hardware RTC, set the system time clock based on GPS UTC + //TODO generalize this by moving into gps.cpp? + timespec ts; + ts.tv_sec = epoch; + ts.tv_nsec = _buf.payload_rx_nav_pvt.nano; + clock_settime(CLOCK_REALTIME, &ts); +#endif + + _gps_position->time_gps_usec = (uint64_t)epoch * 1000000; //TODO: test this + _gps_position->time_gps_usec += (uint64_t)(_buf.payload_rx_nav_pvt.nano * 1e-3f); + } + + _gps_position->timestamp_time = hrt_absolute_time(); + _gps_position->timestamp_velocity = hrt_absolute_time(); + _gps_position->timestamp_variance = hrt_absolute_time(); + _gps_position->timestamp_position = hrt_absolute_time(); + + _rate_count_vel++; + _rate_count_lat_lon++; + + _got_posllh = true; + _got_velned = true; + + ret = 1; + break; + case UBX_MSG_NAV_POSLLH: UBX_TRACE_RXMSG("Rx NAV-POSLLH\n"); @@ -697,7 +785,6 @@ UBX::payload_rx_done(void) _gps_position->fix_type = _buf.payload_rx_nav_sol.gpsFix; _gps_position->s_variance_m_s = (float)_buf.payload_rx_nav_sol.sAcc * 1e-2f; // from cm to m - _gps_position->p_variance_m = (float)_buf.payload_rx_nav_sol.pAcc * 1e-2f; // from cm to m _gps_position->satellites_used = _buf.payload_rx_nav_sol.numSV; _gps_position->timestamp_variance = hrt_absolute_time(); diff --git a/src/drivers/gps/ubx.h b/src/drivers/gps/ubx.h index 65f2dd2ba..219a5762a 100644 --- a/src/drivers/gps/ubx.h +++ b/src/drivers/gps/ubx.h @@ -183,7 +183,7 @@ typedef struct { uint32_t reserved2; } ubx_payload_rx_nav_sol_t; -/* Rx NAV-PVT */ +/* Rx NAV-PVT (ubx8) */ typedef struct { uint32_t iTOW; /**< GPS Time of Week [ms] */ uint16_t year; /**< Year (UTC)*/ @@ -215,9 +215,11 @@ typedef struct { uint16_t pDOP; /**< Position DOP [0.01] */ uint16_t reserved2; uint32_t reserved3; - int32_t headVeh; /**< Heading of vehicle (2-D) [1e-5 deg] */ - uint32_t reserved4; + int32_t headVeh; /**< (ubx8+ only) Heading of vehicle (2-D) [1e-5 deg] */ + uint32_t reserved4; /**< (ubx8+ only) */ } ubx_payload_rx_nav_pvt_t; +#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX7 (sizeof(ubx_payload_rx_nav_pvt_t) - 8) +#define UBX_PAYLOAD_RX_NAV_PVT_SIZE_UBX8 (sizeof(ubx_payload_rx_nav_pvt_t)) /* Rx NAV-TIMEUTC */ typedef struct { @@ -395,6 +397,7 @@ typedef struct { /* General message and payload buffer union */ typedef union { + ubx_payload_rx_nav_pvt_t payload_rx_nav_pvt; ubx_payload_rx_nav_posllh_t payload_rx_nav_posllh; ubx_payload_rx_nav_sol_t payload_rx_nav_sol; ubx_payload_rx_nav_timeutc_t payload_rx_nav_timeutc; @@ -533,6 +536,7 @@ private: uint16_t _ack_waiting_msg; ubx_buf_t _buf; uint32_t _ubx_version; + bool _use_nav_pvt; }; #endif /* UBX_H_ */ diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 53a1638a3..6d361052c 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -741,7 +741,6 @@ MavlinkReceiver::handle_message_hil_gps(mavlink_message_t *msg) hil_gps.timestamp_variance = timestamp; hil_gps.s_variance_m_s = 5.0f; - hil_gps.p_variance_m = hil_gps.eph * hil_gps.eph; hil_gps.timestamp_velocity = timestamp; hil_gps.vel_m_s = (float)gps.vel * 1e-2f; // from cm/s to m/s diff --git a/src/modules/uORB/topics/vehicle_gps_position.h b/src/modules/uORB/topics/vehicle_gps_position.h index dbd59f4f3..80d65cd69 100644 --- a/src/modules/uORB/topics/vehicle_gps_position.h +++ b/src/modules/uORB/topics/vehicle_gps_position.h @@ -61,7 +61,6 @@ struct vehicle_gps_position_s { uint64_t timestamp_variance; float s_variance_m_s; /**< speed accuracy estimate m/s */ - float p_variance_m; /**< position accuracy estimate m */ float c_variance_rad; /**< course accuracy estimate rad */ uint8_t fix_type; /**< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. */ -- cgit v1.2.3 From 7608628e9d3979814557438df0bd4f676ebe49a4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 3 Jul 2014 14:25:46 +0200 Subject: Contributing notes --- CONTRIBUTING.md | 44 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 44 insertions(+) create mode 100644 CONTRIBUTING.md diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md new file mode 100644 index 000000000..a6f5fa7a3 --- /dev/null +++ b/CONTRIBUTING.md @@ -0,0 +1,44 @@ +# Contributing to PX4 Firmware + +We follow the [Github flow](https://guides.github.com/introduction/flow/) development model. + +### Fork the project, then clone your repo + +First [fork and clone](https://help.github.com/articles/fork-a-repo) the project project. + +### Create a feature branch + +*Always* branch off master for new features. + +``` +git checkout -b my_descriptive_branch_name +``` + +### Edit and build the code + +The [developer guide](http://pixhawk.org/dev/start) explains how to set up the development environment on Mac OS, Linux or Windows. Please take note of our [coding style](http://pixhawk.org/dev/code_style) when editing files. + +### Commit your changes + +Always write descriptive commit messages and add a fixes or relates note to them with an [issue number](https://github.com/px4/Firmware/issues) (Github will link these then conveniently) + +**Example:** + +``` +Change how the attitude controller works + +- Fixes rate feed forward +- Allows a local body rate override + +Fixes issue #123 +``` + +### Test your changes + +Since we care about safety, we will regularly ask you for test results. Best is to do a test flight (or bench test where it applies) and upload the logfile from it (on the microSD card in the logs directory) to Google Drive or Dropbox and share the link. + +### Push your changes + +Push changes to your repo and send a [pull request](https://github.com/PX4/Firmware/compare/). + +Make sure to provide some testing feedback and if possible the link to a flight log file. -- cgit v1.2.3 From 74f0301fa1553be85d86f7869d70fdda75b4c7b9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 3 Jul 2014 14:46:06 +0200 Subject: Changed branch name suggestion --- CONTRIBUTING.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index a6f5fa7a3..3bf02fbff 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -11,7 +11,7 @@ First [fork and clone](https://help.github.com/articles/fork-a-repo) the project *Always* branch off master for new features. ``` -git checkout -b my_descriptive_branch_name +git checkout -b mydescriptivebranchname ``` ### Edit and build the code -- cgit v1.2.3 From d7394c7ef973e34d87187420444baad6fcf9854b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 3 Jul 2014 19:00:22 +0200 Subject: mavlink: stack size increased --- src/modules/mavlink/mavlink_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index cf6265f09..f73a58fa2 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1601,7 +1601,7 @@ Mavlink::start(int argc, char *argv[]) task_spawn_cmd(buf, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 1950, + 2700, (main_t)&Mavlink::start_helper, (const char **)argv); -- cgit v1.2.3 From c6c33142ceb6bf59b8c9b8e32e94ae5ea7959dbd Mon Sep 17 00:00:00 2001 From: Andrew Chambers Date: Thu, 3 Jul 2014 11:32:27 -0700 Subject: Using proper math library. Corrected speed variance calculation --- src/modules/uavcan/gnss_receiver.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/modules/uavcan/gnss_receiver.cpp b/src/modules/uavcan/gnss_receiver.cpp index 65a7b4a2a..3e98bdf14 100644 --- a/src/modules/uavcan/gnss_receiver.cpp +++ b/src/modules/uavcan/gnss_receiver.cpp @@ -41,6 +41,7 @@ #include "gnss_receiver.hpp" #include +#include #define MM_PER_CM 10 // Millimeters per centimeter @@ -86,7 +87,7 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure Date: Fri, 4 Jul 2014 15:49:02 +0200 Subject: navigator: takeoff altitude fixed --- src/modules/navigator/mission.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 2e5047e2c..cf6a764bf 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -326,11 +326,12 @@ Mission::set_mission_items() takeoff_alt += _navigator->get_home_position()->alt; } + /* perform takeoff at least to NAV_TAKEOFF_ALT above home/ground, even if first waypoint is lower */ if (_navigator->get_vstatus()->condition_landed) { takeoff_alt = fmaxf(takeoff_alt, _navigator->get_global_position()->alt + _param_takeoff_alt.get()); } else { - takeoff_alt = _navigator->get_home_position()->alt + _param_takeoff_alt.get(); + takeoff_alt = fmaxf(takeoff_alt, _navigator->get_home_position()->alt + _param_takeoff_alt.get()); } mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: takeoff to %.1fm above home", takeoff_alt - _navigator->get_home_position()->alt); -- cgit v1.2.3 From f9696cc68a2a82937ae1189a06edea167c492e00 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Fri, 4 Jul 2014 15:52:45 +0200 Subject: hk micro pcb quad startup script: add comment --- ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb index 369aa1eb4..5bd67a9e4 100644 --- a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb +++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb @@ -1,6 +1,7 @@ #!nsh # # Hobbyking Micro Integrated PCB Quadcopter +# with SimonK ESC firmware and Mystery A1510 motors # # Thomas Gubler # -- cgit v1.2.3 From e97161e96b8de4031746556ab4bd4f96d24a30c8 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 4 Jul 2014 15:53:26 +0200 Subject: mavlink: stack size for main thread increased --- src/modules/mavlink/mavlink_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 026a4d6c9..8dfa32ce8 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -2238,7 +2238,7 @@ Mavlink::start(int argc, char *argv[]) task_spawn_cmd(buf, SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 1950, + 2700, (main_t)&Mavlink::start_helper, (const char **)argv); -- cgit v1.2.3 From f91477212894fc6e1de68c429c51974443b6075b Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Fri, 4 Jul 2014 16:01:10 +0200 Subject: micro pcb quad: remove unnecessary setting --- ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb | 1 - 1 file changed, 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb index 5bd67a9e4..99ffd73a5 100644 --- a/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb +++ b/ROMFS/px4fmu_common/init.d/4020_hk_micro_pcb @@ -26,4 +26,3 @@ then fi set PWM_MIN 1200 -set PWM_DISARMED 900 -- cgit v1.2.3 From d4eae37e478860a59e21f3caceb3d8fc28f9fa7c Mon Sep 17 00:00:00 2001 From: Antonio Sanniravong Date: Fri, 4 Jul 2014 21:00:05 -0400 Subject: Commander: Only consider latest active data link heartbeat for timeout. --- src/modules/commander/commander.cpp | 30 ++++++++++++++++++------------ 1 file changed, 18 insertions(+), 12 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index efa26eb97..699ced1ab 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -767,6 +767,7 @@ int commander_thread_main(int argc, char *argv[]) hrt_abstime last_idle_time = 0; hrt_abstime start_time = 0; + hrt_abstime latest_heartbeat = 0; bool status_changed = true; bool param_init_forced = true; @@ -1367,19 +1368,24 @@ int commander_thread_main(int argc, char *argv[]) } /* data link check */ - if (hrt_absolute_time() < telemetry.heartbeat_time + DL_TIMEOUT) { - /* handle the case where data link was regained */ - if (status.data_link_lost) { - mavlink_log_critical(mavlink_fd, "#audio: data link regained"); - status.data_link_lost = false; - status_changed = true; - } + if (telemetry.heartbeat_time >= latest_heartbeat) { + if (hrt_absolute_time() < telemetry.heartbeat_time + DL_TIMEOUT) { + /* handle the case where data link was regained */ + if (status.data_link_lost) { + mavlink_log_critical(mavlink_fd, "#audio: data link regained"); + status.data_link_lost = false; + status_changed = true; + } - } else { - if (!status.data_link_lost) { - mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: DATA LINK LOST"); - status.data_link_lost = true; - status_changed = true; + /* Only consider data link with most recent heartbeat */ + latest_heartbeat = telemetry.heartbeat_time; + + } else { + if (!status.data_link_lost) { + mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: DATA LINK LOST"); + status.data_link_lost = true; + status_changed = true; + } } } -- cgit v1.2.3 From b9299e68d4147845bab9ed99509b3e50b7c94ae1 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sat, 5 Jul 2014 13:35:12 -0700 Subject: Compiler warning fixes --- src/drivers/blinkm/blinkm.cpp | 2 +- src/lib/geo/geo.c | 14 ++++++------- src/modules/commander/commander.cpp | 8 ++++---- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 23 +++++++++++----------- src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h | 4 ++-- src/modules/systemlib/cpuload.c | 2 +- src/modules/systemlib/systemlib.c | 3 +++ src/systemcmds/param/param.c | 5 +++-- 8 files changed, 33 insertions(+), 28 deletions(-) diff --git a/src/drivers/blinkm/blinkm.cpp b/src/drivers/blinkm/blinkm.cpp index 92e089217..6b14f5945 100644 --- a/src/drivers/blinkm/blinkm.cpp +++ b/src/drivers/blinkm/blinkm.cpp @@ -293,7 +293,7 @@ BlinkM::BlinkM(int bus, int blinkm) : safety_sub_fd(-1), num_of_cells(0), detected_cells_runcount(0), - t_led_color({0}), + t_led_color{0}, t_led_blink(0), led_thread_runcount(0), led_interval(1000), diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c index 212e33ff8..230be9281 100644 --- a/src/lib/geo/geo.c +++ b/src/lib/geo/geo.c @@ -297,12 +297,12 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, do // TO DO - this is messed up and won't compile float start_disp_x = radius * sinf(arc_start_bearing); float start_disp_y = radius * cosf(arc_start_bearing); - float end_disp_x = radius * sinf(_wrapPI(arc_start_bearing + arc_sweep)); - float end_disp_y = radius * cosf(_wrapPI(arc_start_bearing + arc_sweep)); - float lon_start = lon_now + start_disp_x / 111111.0f; - float lat_start = lat_now + start_disp_y * cosf(lat_now) / 111111.0f; - float lon_end = lon_now + end_disp_x / 111111.0f; - float lat_end = lat_now + end_disp_y * cosf(lat_now) / 111111.0f; + float end_disp_x = radius * sinf(_wrapPI((double)(arc_start_bearing + arc_sweep))); + float end_disp_y = radius * cosf(_wrapPI((double)(arc_start_bearing + arc_sweep))); + float lon_start = (float)lon_now + start_disp_x / 111111.0f; + float lat_start = (float)lat_now + start_disp_y * cosf(lat_now) / 111111.0f; + float lon_end = (float)lon_now + end_disp_x / 111111.0f; + float lat_end = (float)lat_now + end_disp_y * cosf(lat_now) / 111111.0f; float dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start); float dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end); @@ -319,7 +319,7 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, do } - crosstrack_error->bearing = _wrapPI(crosstrack_error->bearing); + crosstrack_error->bearing = _wrapPI((double)crosstrack_error->bearing); return_value = OK; return return_value; } diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index efa26eb97..3bf3c857d 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -472,7 +472,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm. // We use an float epsilon delta to test float equality. if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) { - mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", cmd->param1); + mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", (double)cmd->param1); } else { @@ -634,7 +634,7 @@ int commander_thread_main(int argc, char *argv[]) /* welcome user */ warnx("starting"); - char *main_states_str[MAIN_STATE_MAX]; + const char *main_states_str[MAIN_STATE_MAX]; main_states_str[MAIN_STATE_MANUAL] = "MANUAL"; main_states_str[MAIN_STATE_ALTCTL] = "ALTCTL"; main_states_str[MAIN_STATE_POSCTL] = "POSCTL"; @@ -643,7 +643,7 @@ int commander_thread_main(int argc, char *argv[]) main_states_str[MAIN_STATE_AUTO_RTL] = "AUTO_RTL"; main_states_str[MAIN_STATE_ACRO] = "ACRO"; - char *arming_states_str[ARMING_STATE_MAX]; + const char *arming_states_str[ARMING_STATE_MAX]; arming_states_str[ARMING_STATE_INIT] = "INIT"; arming_states_str[ARMING_STATE_STANDBY] = "STANDBY"; arming_states_str[ARMING_STATE_ARMED] = "ARMED"; @@ -652,7 +652,7 @@ int commander_thread_main(int argc, char *argv[]) arming_states_str[ARMING_STATE_REBOOT] = "REBOOT"; arming_states_str[ARMING_STATE_IN_AIR_RESTORE] = "IN_AIR_RESTORE"; - char *nav_states_str[NAVIGATION_STATE_MAX]; + const char *nav_states_str[NAVIGATION_STATE_MAX]; nav_states_str[NAVIGATION_STATE_MANUAL] = "MANUAL"; nav_states_str[NAVIGATION_STATE_ALTCTL] = "ALTCTL"; nav_states_str[NAVIGATION_STATE_POSCTL] = "POSCTL"; diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 000c02e3d..a9556f453 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -414,6 +414,17 @@ FixedwingPositionControl::FixedwingPositionControl() : _attitude_sp_pub(-1), _nav_capabilities_pub(-1), + _att(), + _att_sp(), + _nav_capabilities(), + _manual(), + _airspeed(), + _control_mode(), + _global_pos(), + _pos_sp_triplet(), + _sensor_combined(), + _range_finder(), + /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "fw l1 control")), @@ -433,18 +444,8 @@ FixedwingPositionControl::FixedwingPositionControl() : _airspeed_valid(false), _groundspeed_undershoot(0.0f), _global_pos_valid(false), - _att(), - _att_sp(), - _nav_capabilities(), - _manual(), - _airspeed(), - _control_mode(), - _global_pos(), - _pos_sp_triplet(), - _sensor_combined(), _mTecs(), - _was_pos_control_mode(false), - _range_finder() + _was_pos_control_mode(false) { _nav_capabilities.turn_distance = 0.0f; diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h b/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h index e4e405227..c22e60ae0 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_blocks.h @@ -56,9 +56,9 @@ class BlockOutputLimiter: public SuperBlock { public: // methods - BlockOutputLimiter(SuperBlock *parent, const char *name, bool isAngularLimit = false) : + BlockOutputLimiter(SuperBlock *parent, const char *name, bool fAngularLimit = false) : SuperBlock(parent, name), - _isAngularLimit(isAngularLimit), + _isAngularLimit(fAngularLimit), _min(this, "MIN"), _max(this, "MAX") {}; diff --git a/src/modules/systemlib/cpuload.c b/src/modules/systemlib/cpuload.c index ccc516f39..7aa2f3a5f 100644 --- a/src/modules/systemlib/cpuload.c +++ b/src/modules/systemlib/cpuload.c @@ -67,7 +67,7 @@ __EXPORT void sched_note_switch(FAR struct tcb_s *pFromTcb, FAR struct tcb_s *pT __EXPORT struct system_load_s system_load; -extern FAR struct _TCB *sched_gettcb(pid_t pid); +extern FAR struct tcb_s *sched_gettcb(pid_t pid); void cpuload_initialize_once() { diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c index 9fff3eb88..90d8dd77c 100644 --- a/src/modules/systemlib/systemlib.c +++ b/src/modules/systemlib/systemlib.c @@ -54,6 +54,9 @@ #include "systemlib.h" +// Didn't seem right to include up_internal.h, so direct extern instead. +extern void up_systemreset(void) noreturn_function; + void systemreset(bool to_bootloader) { diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c index f8bff2f6f..235ab7186 100644 --- a/src/systemcmds/param/param.c +++ b/src/systemcmds/param/param.c @@ -46,6 +46,7 @@ #include #include #include +#include #include #include @@ -228,8 +229,8 @@ do_show_print(void *arg, param_t param) if (!(arg == NULL)) { /* start search */ - char *ss = search_string; - char *pp = p_name; + const char *ss = search_string; + const char *pp = p_name; bool mismatch = false; /* XXX this comparison is only ok for trailing wildcards */ -- cgit v1.2.3 From 4f06e9bdc9c0c6aa6712797a671b56f034656c41 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 6 Jul 2014 15:16:39 +0200 Subject: Move a seldomly used module to test config --- makefiles/config_px4fmu-v2_default.mk | 1 - makefiles/config_px4fmu-v2_test.mk | 1 + 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index 4b6b0a4d2..8e83df391 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -33,7 +33,6 @@ MODULES += drivers/hil MODULES += drivers/hott/hott_telemetry MODULES += drivers/hott/hott_sensors MODULES += drivers/blinkm -MODULES += drivers/roboclaw MODULES += drivers/airspeed MODULES += drivers/ets_airspeed MODULES += drivers/meas_airspeed diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk index 66b2157ed..66d9efbf8 100644 --- a/makefiles/config_px4fmu-v2_test.mk +++ b/makefiles/config_px4fmu-v2_test.mk @@ -25,6 +25,7 @@ MODULES += drivers/l3gd20 MODULES += drivers/hmc5883 MODULES += drivers/ms5611 MODULES += drivers/pca8574 +MODULES += drivers/roboclaw MODULES += systemcmds/perf MODULES += systemcmds/reboot MODULES += systemcmds/tests -- cgit v1.2.3 From 43a1c1b5f600d5608a861d35d539319de1170923 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 6 Jul 2014 15:33:54 +0200 Subject: Code style improvement, fix linter warning --- src/modules/uavcan/esc_controller.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/src/modules/uavcan/esc_controller.cpp b/src/modules/uavcan/esc_controller.cpp index bde4d2a7f..f603d9448 100644 --- a/src/modules/uavcan/esc_controller.cpp +++ b/src/modules/uavcan/esc_controller.cpp @@ -50,10 +50,8 @@ UavcanEscController::UavcanEscController(uavcan::INode &node) : int UavcanEscController::init() { - int res = -1; - // ESC status subscription - res = _uavcan_sub_status.start(StatusCbBinder(this, &UavcanEscController::esc_status_sub_cb)); + int res = _uavcan_sub_status.start(StatusCbBinder(this, &UavcanEscController::esc_status_sub_cb)); if (res < 0) { warnx("ESC status sub failed %i", res); -- cgit v1.2.3 From 2669f7f3af65921d4abbf3850cd62e48f2eeeec7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 6 Jul 2014 15:34:50 +0200 Subject: Fix mixer limiter to never output min for an input of max + 1 quantum --- src/modules/uavcan/uavcan_main.cpp | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 5bc437670..27e77e9c5 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -301,9 +301,7 @@ int UavcanNode::run() // iterate actuators for (unsigned i = 0; i < outputs.noutputs; i++) { // last resort: catch NaN, INF and out-of-band errors - if (!isfinite(outputs.output[i]) || - outputs.output[i] < -1.0f || - outputs.output[i] > 1.0f) { + if (!isfinite(outputs.output[i])) { /* * Value is NaN, INF or out of band - set to the minimum value. * This will be clearly visible on the servo status and will limit the risk of accidentally @@ -311,6 +309,18 @@ int UavcanNode::run() */ outputs.output[i] = -1.0f; } + + // limit outputs to valid range + + // never go below min + if (outputs.output[i] < -1.0f) { + outputs.output[i] = -1.0f; + } + + // never go below max + if (outputs.output[i] > 1.0f) { + outputs.output[i] = 1.0f; + } } // Output to the bus -- cgit v1.2.3 From bd5d3ebf70dc9e1aef106b60a840c17824d35b9b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 6 Jul 2014 16:08:37 +0200 Subject: telemetry_statur: use 4 separate topics --- src/modules/commander/commander.cpp | 87 +++++++++++++++++++----------- src/modules/mavlink/mavlink_receiver.cpp | 86 +++++++++++++++-------------- src/modules/sdlog2/sdlog2.c | 31 ++++++----- src/modules/sdlog2/sdlog2_format.h | 8 +++ src/modules/sdlog2/sdlog2_messages.h | 35 +++++++----- src/modules/uORB/objects_common.cpp | 5 +- src/modules/uORB/topics/telemetry_status.h | 14 ++++- 7 files changed, 166 insertions(+), 100 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 699ced1ab..0003ec106 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -767,7 +767,6 @@ int commander_thread_main(int argc, char *argv[]) hrt_abstime last_idle_time = 0; hrt_abstime start_time = 0; - hrt_abstime latest_heartbeat = 0; bool status_changed = true; bool param_init_forced = true; @@ -797,10 +796,16 @@ int commander_thread_main(int argc, char *argv[]) struct offboard_control_setpoint_s sp_offboard; memset(&sp_offboard, 0, sizeof(sp_offboard)); - /* Subscribe to telemetry status */ - int telemetry_sub = orb_subscribe(ORB_ID(telemetry_status)); - struct telemetry_status_s telemetry; - memset(&telemetry, 0, sizeof(telemetry)); + /* Subscribe to telemetry status topics */ + int telemetry_subs[TELEMETRY_STATUS_ORB_ID_NUM]; + uint64_t telemetry_last_heartbeat[TELEMETRY_STATUS_ORB_ID_NUM]; + bool telemetry_lost[TELEMETRY_STATUS_ORB_ID_NUM]; + + for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) { + telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]); + telemetry_last_heartbeat[i] = 0; + telemetry_lost[i] = true; + } /* Subscribe to global position */ int global_position_sub = orb_subscribe(ORB_ID(vehicle_global_position)); @@ -882,7 +887,6 @@ int commander_thread_main(int argc, char *argv[]) bool arming_state_changed = false; bool main_state_changed = false; bool failsafe_old = false; - bool system_checked = false; while (!thread_should_exit) { @@ -939,15 +943,6 @@ int commander_thread_main(int argc, char *argv[]) param_get(_param_enable_datalink_loss, &datalink_loss_enabled); } - /* Perform system checks (again) once params are loaded and MAVLink is up. */ - if (!system_checked && mavlink_fd && - (telemetry.heartbeat_time > 0) && - (hrt_elapsed_time(&telemetry.heartbeat_time) < 1 * 1000 * 1000)) { - - (void)rc_calibration_check(mavlink_fd); - system_checked = true; - } - orb_check(sp_man_sub, &updated); if (updated) { @@ -960,10 +955,26 @@ int commander_thread_main(int argc, char *argv[]) orb_copy(ORB_ID(offboard_control_setpoint), sp_offboard_sub, &sp_offboard); } - orb_check(telemetry_sub, &updated); + for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) { + orb_check(telemetry_subs[i], &updated); - if (updated) { - orb_copy(ORB_ID(telemetry_status), telemetry_sub, &telemetry); + if (updated) { + struct telemetry_status_s telemetry; + memset(&telemetry, 0, sizeof(telemetry)); + + orb_copy(telemetry_status_orb_id[i], telemetry_subs[i], &telemetry); + + /* perform system checks when new telemetry link connected */ + if (mavlink_fd && + telemetry_last_heartbeat[i] == 0 && + telemetry.heartbeat_time > 0 && + hrt_elapsed_time(&telemetry.heartbeat_time) < DL_TIMEOUT) { + + (void)rc_calibration_check(mavlink_fd); + } + + telemetry_last_heartbeat[i] = telemetry.heartbeat_time; + } } orb_check(sensor_sub, &updated); @@ -1367,28 +1378,40 @@ int commander_thread_main(int argc, char *argv[]) } } - /* data link check */ - if (telemetry.heartbeat_time >= latest_heartbeat) { - if (hrt_absolute_time() < telemetry.heartbeat_time + DL_TIMEOUT) { + /* data links check */ + bool have_link = false; + for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) { + if (hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) { /* handle the case where data link was regained */ - if (status.data_link_lost) { - mavlink_log_critical(mavlink_fd, "#audio: data link regained"); - status.data_link_lost = false; - status_changed = true; + if (telemetry_lost[i]) { + mavlink_log_critical(mavlink_fd, "#audio: data link %i regained", i); + telemetry_lost[i] = false; } - - /* Only consider data link with most recent heartbeat */ - latest_heartbeat = telemetry.heartbeat_time; + have_link = true; } else { - if (!status.data_link_lost) { - mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: DATA LINK LOST"); - status.data_link_lost = true; - status_changed = true; + if (!telemetry_lost[i]) { + mavlink_log_critical(mavlink_fd, "#audio: data link %i lost", i); + telemetry_lost[i] = true; } } } + if (have_link) { + /* handle the case where data link was regained */ + if (status.data_link_lost) { + status.data_link_lost = false; + status_changed = true; + } + + } else { + if (!status.data_link_lost) { + mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: ALL DATA LINKS LOST"); + status.data_link_lost = true; + status_changed = true; + } + } + /* handle commands last, as the system needs to be updated to handle them */ orb_check(cmd_sub, &updated); diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 6d361052c..60da9c47d 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -421,32 +421,35 @@ MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message void MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) { - mavlink_radio_status_t rstatus; - mavlink_msg_radio_status_decode(msg, &rstatus); - - struct telemetry_status_s tstatus; - memset(&tstatus, 0, sizeof(tstatus)); - - tstatus.timestamp = hrt_absolute_time(); - tstatus.heartbeat_time = _telemetry_heartbeat_time; - tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO; - tstatus.rssi = rstatus.rssi; - tstatus.remote_rssi = rstatus.remrssi; - tstatus.txbuf = rstatus.txbuf; - tstatus.noise = rstatus.noise; - tstatus.remote_noise = rstatus.remnoise; - tstatus.rxerrors = rstatus.rxerrors; - tstatus.fixed = rstatus.fixed; - - if (_telemetry_status_pub < 0) { - _telemetry_status_pub = orb_advertise(ORB_ID(telemetry_status), &tstatus); + /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */ + if (_mavlink->get_channel() < TELEMETRY_STATUS_ORB_ID_NUM) { + mavlink_radio_status_t rstatus; + mavlink_msg_radio_status_decode(msg, &rstatus); + + struct telemetry_status_s tstatus; + memset(&tstatus, 0, sizeof(tstatus)); + + tstatus.timestamp = hrt_absolute_time(); + tstatus.heartbeat_time = _telemetry_heartbeat_time; + tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO; + tstatus.rssi = rstatus.rssi; + tstatus.remote_rssi = rstatus.remrssi; + tstatus.txbuf = rstatus.txbuf; + tstatus.noise = rstatus.noise; + tstatus.remote_noise = rstatus.remnoise; + tstatus.rxerrors = rstatus.rxerrors; + tstatus.fixed = rstatus.fixed; + + if (_telemetry_status_pub < 0) { + _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus); - } else { - orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus); - } + } else { + orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus); + } - /* this means that heartbeats alone won't be published to the radio status no more */ - _radio_status_available = true; + /* this means that heartbeats alone won't be published to the radio status no more */ + _radio_status_available = true; + } } void @@ -475,28 +478,31 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) void MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) { - mavlink_heartbeat_t hb; - mavlink_msg_heartbeat_decode(msg, &hb); + /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */ + if (_mavlink->get_channel() < TELEMETRY_STATUS_ORB_ID_NUM) { + mavlink_heartbeat_t hb; + mavlink_msg_heartbeat_decode(msg, &hb); - /* ignore own heartbeats, accept only heartbeats from GCS */ - if (msg->sysid != mavlink_system.sysid && hb.type == MAV_TYPE_GCS) { - _telemetry_heartbeat_time = hrt_absolute_time(); + /* ignore own heartbeats, accept only heartbeats from GCS */ + if (msg->sysid != mavlink_system.sysid && hb.type == MAV_TYPE_GCS) { + _telemetry_heartbeat_time = hrt_absolute_time(); - /* if no radio status messages arrive, lets at least publish that heartbeats were received */ - if (!_radio_status_available) { + /* if no radio status messages arrive, lets at least publish that heartbeats were received */ + if (!_radio_status_available) { - struct telemetry_status_s tstatus; - memset(&tstatus, 0, sizeof(tstatus)); + struct telemetry_status_s tstatus; + memset(&tstatus, 0, sizeof(tstatus)); - tstatus.timestamp = _telemetry_heartbeat_time; - tstatus.heartbeat_time = _telemetry_heartbeat_time; - tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC; + tstatus.timestamp = _telemetry_heartbeat_time; + tstatus.heartbeat_time = _telemetry_heartbeat_time; + tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC; - if (_telemetry_status_pub < 0) { - _telemetry_status_pub = orb_advertise(ORB_ID(telemetry_status), &tstatus); + if (_telemetry_status_pub < 0) { + _telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus); - } else { - orb_publish(ORB_ID(telemetry_status), _telemetry_status_pub, &tstatus); + } else { + orb_publish(telemetry_status_orb_id[_mavlink->get_channel()], _telemetry_status_pub, &tstatus); + } } } } diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 39e5b6c41..0d36fa2c6 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -979,7 +979,7 @@ int sdlog2_thread_main(int argc, char *argv[]) struct log_GVSP_s log_GVSP; struct log_BATT_s log_BATT; struct log_DIST_s log_DIST; - struct log_TELE_s log_TELE; + struct log_TEL_s log_TEL; struct log_EST0_s log_EST0; struct log_EST1_s log_EST1; struct log_PWR_s log_PWR; @@ -1019,7 +1019,7 @@ int sdlog2_thread_main(int argc, char *argv[]) int esc_sub; int global_vel_sp_sub; int battery_sub; - int telemetry_sub; + int telemetry_subs[TELEMETRY_STATUS_ORB_ID_NUM]; int range_finder_sub; int estimator_status_sub; int tecs_status_sub; @@ -1049,7 +1049,9 @@ int sdlog2_thread_main(int argc, char *argv[]) subs.esc_sub = orb_subscribe(ORB_ID(esc_status)); subs.global_vel_sp_sub = orb_subscribe(ORB_ID(vehicle_global_velocity_setpoint)); subs.battery_sub = orb_subscribe(ORB_ID(battery_status)); - subs.telemetry_sub = orb_subscribe(ORB_ID(telemetry_status)); + for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) { + subs.telemetry_subs[i] = orb_subscribe(telemetry_status_orb_id[i]); + } subs.range_finder_sub = orb_subscribe(ORB_ID(sensor_range_finder)); subs.estimator_status_sub = orb_subscribe(ORB_ID(estimator_status)); subs.tecs_status_sub = orb_subscribe(ORB_ID(tecs_status)); @@ -1479,16 +1481,19 @@ int sdlog2_thread_main(int argc, char *argv[]) } /* --- TELEMETRY --- */ - if (copy_if_updated(ORB_ID(telemetry_status), subs.telemetry_sub, &buf.telemetry)) { - log_msg.msg_type = LOG_TELE_MSG; - log_msg.body.log_TELE.rssi = buf.telemetry.rssi; - log_msg.body.log_TELE.remote_rssi = buf.telemetry.remote_rssi; - log_msg.body.log_TELE.noise = buf.telemetry.noise; - log_msg.body.log_TELE.remote_noise = buf.telemetry.remote_noise; - log_msg.body.log_TELE.rxerrors = buf.telemetry.rxerrors; - log_msg.body.log_TELE.fixed = buf.telemetry.fixed; - log_msg.body.log_TELE.txbuf = buf.telemetry.txbuf; - LOGBUFFER_WRITE_AND_COUNT(TELE); + for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) { + if (copy_if_updated(telemetry_status_orb_id[i], subs.telemetry_subs[i], &buf.telemetry)) { + log_msg.msg_type = LOG_TEL0_MSG + i; + log_msg.body.log_TEL.rssi = buf.telemetry.rssi; + log_msg.body.log_TEL.remote_rssi = buf.telemetry.remote_rssi; + log_msg.body.log_TEL.noise = buf.telemetry.noise; + log_msg.body.log_TEL.remote_noise = buf.telemetry.remote_noise; + log_msg.body.log_TEL.rxerrors = buf.telemetry.rxerrors; + log_msg.body.log_TEL.fixed = buf.telemetry.fixed; + log_msg.body.log_TEL.txbuf = buf.telemetry.txbuf; + log_msg.body.log_TEL.heartbeat_time = buf.telemetry.heartbeat_time; + LOGBUFFER_WRITE_AND_COUNT(TEL); + } } /* --- BOTTOM DISTANCE --- */ diff --git a/src/modules/sdlog2/sdlog2_format.h b/src/modules/sdlog2/sdlog2_format.h index dc5e6c8bd..aff0e3f48 100644 --- a/src/modules/sdlog2/sdlog2_format.h +++ b/src/modules/sdlog2/sdlog2_format.h @@ -91,6 +91,14 @@ struct log_format_s { .labels = _labels \ } +#define LOG_FORMAT_S(_name, _struct_name, _format, _labels) { \ + .type = LOG_##_name##_MSG, \ + .length = sizeof(struct log_##_struct_name##_s) + LOG_PACKET_HEADER_LEN, \ + .name = #_name, \ + .format = _format, \ + .labels = _labels \ + } + #define LOG_FORMAT_MSG 0x80 #define LOG_PACKET_SIZE(_name) LOG_PACKET_HEADER_LEN + sizeof(struct log_##_name##_s) diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 8c05e87c5..08a87e179 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -276,18 +276,7 @@ struct log_DIST_s { uint8_t flags; }; -/* --- TELE - TELEMETRY STATUS --- */ -#define LOG_TELE_MSG 22 -struct log_TELE_s { - uint8_t rssi; - uint8_t remote_rssi; - uint8_t noise; - uint8_t remote_noise; - uint16_t rxerrors; - uint16_t fixed; - uint8_t txbuf; -}; - +// ID 22 available // ID 23 available /* --- PWR - ONBOARD POWER SYSTEM --- */ @@ -385,6 +374,23 @@ struct log_EST1_s { float s[16]; }; +/* --- TEL0..3 - TELEMETRY STATUS --- */ +#define LOG_TEL0_MSG 34 +#define LOG_TEL1_MSG 35 +#define LOG_TEL2_MSG 36 +#define LOG_TEL3_MSG 37 +struct log_TEL_s { + uint8_t rssi; + uint8_t remote_rssi; + uint8_t noise; + uint8_t remote_noise; + uint16_t rxerrors; + uint16_t fixed; + uint8_t txbuf; + uint64_t heartbeat_time; +}; + + /********** SYSTEM MESSAGES, ID > 0x80 **********/ /* --- TIME - TIME STAMP --- */ @@ -432,7 +438,10 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"), LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"), LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"), - LOG_FORMAT(TELE, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf"), + LOG_FORMAT_S(TEL0, TEL, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), + LOG_FORMAT_S(TEL1, TEL, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), + LOG_FORMAT_S(TEL2, TEL, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), + LOG_FORMAT_S(TEL3, TEL, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), LOG_FORMAT(EST0, "ffffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,nStat,fNaN,fHealth,fTOut"), LOG_FORMAT(EST1, "ffffffffffffffff", "s12,s13,s14,s15,s16,s17,s18,s19,s20,s21,s22,s23,s24,s25,s26,s27"), LOG_FORMAT(PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"), diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp index 687fc1d4a..9b118205e 100644 --- a/src/modules/uORB/objects_common.cpp +++ b/src/modules/uORB/objects_common.cpp @@ -186,7 +186,10 @@ ORB_DEFINE(actuator_outputs_2, struct actuator_outputs_s); ORB_DEFINE(actuator_outputs_3, struct actuator_outputs_s); #include "topics/telemetry_status.h" -ORB_DEFINE(telemetry_status, struct telemetry_status_s); +ORB_DEFINE(telemetry_status_0, struct telemetry_status_s); +ORB_DEFINE(telemetry_status_1, struct telemetry_status_s); +ORB_DEFINE(telemetry_status_2, struct telemetry_status_s); +ORB_DEFINE(telemetry_status_3, struct telemetry_status_s); #include "topics/debug_key_value.h" ORB_DEFINE(debug_key_value, struct debug_key_value_s); diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h index e9e00d76c..c4b99d520 100644 --- a/src/modules/uORB/topics/telemetry_status.h +++ b/src/modules/uORB/topics/telemetry_status.h @@ -72,6 +72,18 @@ struct telemetry_status_s { * @} */ -ORB_DECLARE(telemetry_status); +ORB_DECLARE(telemetry_status_0); +ORB_DECLARE(telemetry_status_1); +ORB_DECLARE(telemetry_status_2); +ORB_DECLARE(telemetry_status_3); + +#define TELEMETRY_STATUS_ORB_ID_NUM 4 + +static const struct orb_metadata *telemetry_status_orb_id[TELEMETRY_STATUS_ORB_ID_NUM] = { + ORB_ID(telemetry_status_0), + ORB_ID(telemetry_status_1), + ORB_ID(telemetry_status_2), + ORB_ID(telemetry_status_3), +}; #endif /* TOPIC_TELEMETRY_STATUS_H */ -- cgit v1.2.3 From 54b55c37c7ffec5c340f100d2027e91971967793 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 6 Jul 2014 17:33:50 +0200 Subject: Reduce excessive stack sizes for FW estimation / control apps --- src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp | 2 +- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index e4f805dc0..5d768b73d 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -1533,7 +1533,7 @@ FixedwingEstimator::start() _estimator_task = task_spawn_cmd("ekf_att_pos_estimator", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 40, - 6000, + 5000, (main_t)&FixedwingEstimator::task_main_trampoline, nullptr); diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 000c02e3d..6c86544fa 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -1449,7 +1449,7 @@ FixedwingPositionControl::start() _control_task = task_spawn_cmd("fw_pos_control_l1", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, - 4048, + 3500, (main_t)&FixedwingPositionControl::task_main_trampoline, nullptr); -- cgit v1.2.3 From 29eab09912ef38eca75b926d5006c0c59b4082b7 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 6 Jul 2014 17:58:21 +0200 Subject: sdlog2: TEL message format fixed --- src/modules/sdlog2/sdlog2_messages.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 08a87e179..87f7f718f 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -438,10 +438,10 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(GVSP, "fff", "VX,VY,VZ"), LOG_FORMAT(BATT, "ffff", "V,VFilt,C,Discharged"), LOG_FORMAT(DIST, "ffB", "Bottom,BottomRate,Flags"), - LOG_FORMAT_S(TEL0, TEL, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), - LOG_FORMAT_S(TEL1, TEL, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), - LOG_FORMAT_S(TEL2, TEL, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), - LOG_FORMAT_S(TEL3, TEL, "BBBBHHB", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), + LOG_FORMAT_S(TEL0, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), + LOG_FORMAT_S(TEL1, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), + LOG_FORMAT_S(TEL2, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), + LOG_FORMAT_S(TEL3, TEL, "BBBBHHBQ", "RSSI,RemRSSI,Noise,RemNoise,RXErr,Fixed,TXBuf,HbTime"), LOG_FORMAT(EST0, "ffffffffffffBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,nStat,fNaN,fHealth,fTOut"), LOG_FORMAT(EST1, "ffffffffffffffff", "s12,s13,s14,s15,s16,s17,s18,s19,s20,s21,s22,s23,s24,s25,s26,s27"), LOG_FORMAT(PWR, "fffBBBBB", "Periph5V,Servo5V,RSSI,UsbOk,BrickOk,ServoOk,PeriphOC,HipwrOC"), -- cgit v1.2.3 From 278aafe939bc20c2882d17b6e21da5ab38d1f400 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 6 Jul 2014 11:06:14 -0700 Subject: Bring everything up to double --- src/lib/geo/geo.c | 22 ++++++++++------------ 1 file changed, 10 insertions(+), 12 deletions(-) diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c index 230be9281..e600976ce 100644 --- a/src/lib/geo/geo.c +++ b/src/lib/geo/geo.c @@ -294,23 +294,21 @@ __EXPORT int get_distance_to_arc(struct crosstrack_error_s *crosstrack_error, do // calculate the position of the start and end points. We should not be doing this often // as this function generally will not be called repeatedly when we are out of the sector. - // TO DO - this is messed up and won't compile - float start_disp_x = radius * sinf(arc_start_bearing); - float start_disp_y = radius * cosf(arc_start_bearing); - float end_disp_x = radius * sinf(_wrapPI((double)(arc_start_bearing + arc_sweep))); - float end_disp_y = radius * cosf(_wrapPI((double)(arc_start_bearing + arc_sweep))); - float lon_start = (float)lon_now + start_disp_x / 111111.0f; - float lat_start = (float)lat_now + start_disp_y * cosf(lat_now) / 111111.0f; - float lon_end = (float)lon_now + end_disp_x / 111111.0f; - float lat_end = (float)lat_now + end_disp_y * cosf(lat_now) / 111111.0f; - float dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start); - float dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end); + double start_disp_x = (double)radius * sin(arc_start_bearing); + double start_disp_y = (double)radius * cos(arc_start_bearing); + double end_disp_x = (double)radius * sin(_wrapPI((double)(arc_start_bearing + arc_sweep))); + double end_disp_y = (double)radius * cos(_wrapPI((double)(arc_start_bearing + arc_sweep))); + double lon_start = lon_now + start_disp_x / 111111.0; + double lat_start = lat_now + start_disp_y * cos(lat_now) / 111111.0; + double lon_end = lon_now + end_disp_x / 111111.0; + double lat_end = lat_now + end_disp_y * cos(lat_now) / 111111.0; + double dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start); + double dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end); if (dist_to_start < dist_to_end) { crosstrack_error->distance = dist_to_start; crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_start, lon_start); - } else { crosstrack_error->past_end = true; crosstrack_error->distance = dist_to_end; -- cgit v1.2.3 From d2a2297a14bf2f4dbb71a6ed20c76617e93b14a2 Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 6 Jul 2014 11:24:39 -0700 Subject: Fixes #1130 --- src/modules/px4iofirmware/i2c.c | 3 +++ src/modules/px4iofirmware/px4io.h | 4 ++-- src/modules/px4iofirmware/registers.c | 2 +- src/modules/px4iofirmware/sbus.c | 4 ++-- 4 files changed, 8 insertions(+), 5 deletions(-) diff --git a/src/modules/px4iofirmware/i2c.c b/src/modules/px4iofirmware/i2c.c index 76762c0fc..6d1d1fc2d 100644 --- a/src/modules/px4iofirmware/i2c.c +++ b/src/modules/px4iofirmware/i2c.c @@ -64,12 +64,15 @@ #define rCCR REG(STM32_I2C_CCR_OFFSET) #define rTRISE REG(STM32_I2C_TRISE_OFFSET) +void i2c_reset(void); static int i2c_interrupt(int irq, void *context); static void i2c_rx_setup(void); static void i2c_tx_setup(void); static void i2c_rx_complete(void); static void i2c_tx_complete(void); +#ifdef DEBUG static void i2c_dump(void); +#endif static DMA_HANDLE rx_dma; static DMA_HANDLE tx_dma; diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h index ca175bfbc..b00a96717 100644 --- a/src/modules/px4iofirmware/px4io.h +++ b/src/modules/px4iofirmware/px4io.h @@ -219,8 +219,8 @@ extern bool dsm_input(uint16_t *values, uint16_t *num_values); extern void dsm_bind(uint16_t cmd, int pulses); extern int sbus_init(const char *device); extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels); -extern bool sbus1_output(uint16_t *values, uint16_t num_values); -extern bool sbus2_output(uint16_t *values, uint16_t num_values); +extern void sbus1_output(uint16_t *values, uint16_t num_values); +extern void sbus2_output(uint16_t *values, uint16_t num_values); /** global debug level for isr_debug() */ extern volatile uint8_t debug_level; diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 50108ea1b..b37259997 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -711,7 +711,7 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val { #define SELECT_PAGE(_page_name) \ do { \ - *values = &_page_name[0]; \ + *values = (uint16_t *)&_page_name[0]; \ *num_values = sizeof(_page_name) / sizeof(_page_name[0]); \ } while(0) diff --git a/src/modules/px4iofirmware/sbus.c b/src/modules/px4iofirmware/sbus.c index 70ccab180..0f0414148 100644 --- a/src/modules/px4iofirmware/sbus.c +++ b/src/modules/px4iofirmware/sbus.c @@ -116,14 +116,14 @@ sbus_init(const char *device) return sbus_fd; } -bool +void sbus1_output(uint16_t *values, uint16_t num_values) { char a = 'A'; write(sbus_fd, &a, 1); } -bool +void sbus2_output(uint16_t *values, uint16_t num_values) { char b = 'B'; -- cgit v1.2.3 From ef6c99c1ab4ebce2378bfeef1813b6e9d01367ed Mon Sep 17 00:00:00 2001 From: px4dev Date: Sun, 6 Jul 2014 11:40:28 -0700 Subject: Restructure the locking around SPI transfers --- src/drivers/device/spi.cpp | 62 ++++++++++++++++++++++------------------------ src/drivers/device/spi.h | 2 ++ 2 files changed, 32 insertions(+), 32 deletions(-) diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp index fed6c312c..57cef34d2 100644 --- a/src/drivers/device/spi.cpp +++ b/src/drivers/device/spi.cpp @@ -133,26 +133,44 @@ SPI::probe() int SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len) { - irqstate_t state; + int result; if ((send == nullptr) && (recv == nullptr)) return -EINVAL; + LockMode mode = up_interrupt_context() ? LOCK_NONE : locking_mode; + /* lock the bus as required */ - if (!up_interrupt_context()) { - switch (locking_mode) { - default: - case LOCK_PREEMPTION: - state = irqsave(); - break; - case LOCK_THREADS: - SPI_LOCK(_dev, true); - break; - case LOCK_NONE: - break; + switch (mode) { + default: + case LOCK_PREEMPTION: + { + irqstate_t state = irqsave(); + result = _transfer(send, recv, len); + irqrestore(state); } + break; + case LOCK_THREADS: + SPI_LOCK(_dev, true); + result = _transfer(send, recv, len); + SPI_LOCK(_dev, false); + break; + case LOCK_NONE: + result = _transfer(send, recv, len); + break; } + return result; +} +void +SPI::set_frequency(uint32_t frequency) +{ + _frequency = frequency; +} + +int +SPI::_transfer(uint8_t *send, uint8_t *recv, unsigned len) +{ SPI_SETFREQUENCY(_dev, _frequency); SPI_SETMODE(_dev, _mode); SPI_SETBITS(_dev, 8); @@ -164,27 +182,7 @@ SPI::transfer(uint8_t *send, uint8_t *recv, unsigned len) /* and clean up */ SPI_SELECT(_dev, _device, false); - if (!up_interrupt_context()) { - switch (locking_mode) { - default: - case LOCK_PREEMPTION: - irqrestore(state); - break; - case LOCK_THREADS: - SPI_LOCK(_dev, false); - break; - case LOCK_NONE: - break; - } - } - return OK; } -void -SPI::set_frequency(uint32_t frequency) -{ - _frequency = frequency; -} - } // namespace device diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h index 299575dc5..8e943b3f2 100644 --- a/src/drivers/device/spi.h +++ b/src/drivers/device/spi.h @@ -129,6 +129,8 @@ private: enum spi_mode_e _mode; uint32_t _frequency; struct spi_dev_s *_dev; + + int _transfer(uint8_t *send, uint8_t *recv, unsigned len); }; } // namespace device -- cgit v1.2.3 From 06f08ad04d4cb21047944f350e4a75e88914e1e1 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 6 Jul 2014 21:37:26 +0200 Subject: commander: require home position for MISSION, fallback to LOITER --- src/modules/commander/commander.cpp | 7 +++++++ src/modules/commander/state_machine_helper.cpp | 2 +- 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index efa26eb97..1da364aa5 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1718,6 +1718,13 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin } print_reject_mode(status, "AUTO_MISSION"); + + // fallback to LOITER if home position not set + res = main_state_transition(status, MAIN_STATE_AUTO_LOITER); + + if (res != TRANSITION_DENIED) { + break; // changed successfully or already in this state + } } // fallback to POSCTL diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 423ce2f23..7fb2e08db 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -271,7 +271,6 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta } break; - case MAIN_STATE_AUTO_MISSION: case MAIN_STATE_AUTO_LOITER: /* need global position estimate */ if (status->condition_global_position_valid) { @@ -279,6 +278,7 @@ main_state_transition(struct vehicle_status_s *status, main_state_t new_main_sta } break; + case MAIN_STATE_AUTO_MISSION: case MAIN_STATE_AUTO_RTL: /* need global position and home position */ if (status->condition_global_position_valid && status->condition_home_position_valid) { -- cgit v1.2.3 From 91537934c4ef33444cf582f8a309443d77b3e575 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 6 Jul 2014 14:58:27 -0700 Subject: Better logging --- src/modules/mavlink/mavlink_ftp.cpp | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index ca846a465..b2e6e9d30 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -199,12 +199,18 @@ MavlinkFTP::ErrorCode MavlinkFTP::_workList(Request *req) { auto hdr = req->header(); - DIR *dp = opendir(req->dataAsCString()); + + char dirPath[kMaxDataLength]; + strncpy(dirPath, req->dataAsCString(), kMaxDataLength); + + DIR *dp = opendir(dirPath); if (dp == nullptr) { - printf("FTP: can't open path '%s'\n", req->dataAsCString()); + printf("FTP: can't open path '%s'\n", dirPath); return kErrNotDir; } + + printf("FTP: list %s\n", dirPath); ErrorCode errorCode = kErrNone; struct dirent entry, *result = nullptr; @@ -216,6 +222,7 @@ MavlinkFTP::_workList(Request *req) for (;;) { // read the directory entry if (readdir_r(dp, &entry, &result)) { + printf("FTP: list %s readdir_r failure\n", dirPath); errorCode = kErrIO; break; } @@ -251,8 +258,8 @@ MavlinkFTP::_workList(Request *req) // copy the name, which we know will fit strcpy((char *)&hdr->data[offset], entry.d_name); + printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset]); offset += strlen(entry.d_name) + 1; - printf("FTP: list %s\n", entry.d_name); } closedir(dp); -- cgit v1.2.3 From 324322cb29720dd78b6eb534bb679532d5ed83f2 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 Jul 2014 02:10:09 +0400 Subject: UAVCAN ESC perf counters --- src/modules/uavcan/esc_controller.cpp | 32 ++++++++++++++++++++++++-------- src/modules/uavcan/esc_controller.hpp | 8 ++++++++ 2 files changed, 32 insertions(+), 8 deletions(-) diff --git a/src/modules/uavcan/esc_controller.cpp b/src/modules/uavcan/esc_controller.cpp index f603d9448..406eba88c 100644 --- a/src/modules/uavcan/esc_controller.cpp +++ b/src/modules/uavcan/esc_controller.cpp @@ -48,6 +48,12 @@ UavcanEscController::UavcanEscController(uavcan::INode &node) : { } +UavcanEscController::~UavcanEscController() +{ + perf_free(_perfcnt_invalid_input); + perf_free(_perfcnt_scaling_error); +} + int UavcanEscController::init() { // ESC status subscription @@ -67,8 +73,10 @@ int UavcanEscController::init() void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) { - assert(outputs != nullptr); - assert(num_outputs <= MAX_ESCS); + if ((outputs == nullptr) || (num_outputs > MAX_ESCS)) { + perf_count(_perfcnt_invalid_input); + return; + } /* * Rate limiting - we don't want to congest the bus @@ -89,13 +97,21 @@ void UavcanEscController::update_outputs(float *outputs, unsigned num_outputs) for (unsigned i = 0; i < num_outputs; i++) { float scaled = (outputs[i] + 1.0F) * 0.5F * uavcan::equipment::esc::RawCommand::CMD_MAX; - if (scaled < 1.0F) + if (scaled < 1.0F) { scaled = 1.0F; // Since we're armed, we don't want to stop it completely - - assert(scaled >= uavcan::equipment::esc::RawCommand::CMD_MIN); - assert(scaled <= uavcan::equipment::esc::RawCommand::CMD_MAX); - - msg.cmd.push_back(scaled); + } + + if (scaled < uavcan::equipment::esc::RawCommand::CMD_MIN) { + scaled = uavcan::equipment::esc::RawCommand::CMD_MIN; + perf_count(_perfcnt_scaling_error); + } else if (scaled > uavcan::equipment::esc::RawCommand::CMD_MAX) { + scaled = uavcan::equipment::esc::RawCommand::CMD_MAX; + perf_count(_perfcnt_scaling_error); + } else { + ; // Correct value + } + + msg.cmd.push_back(static_cast(scaled)); } } diff --git a/src/modules/uavcan/esc_controller.hpp b/src/modules/uavcan/esc_controller.hpp index 0ed0c59b5..559ede561 100644 --- a/src/modules/uavcan/esc_controller.hpp +++ b/src/modules/uavcan/esc_controller.hpp @@ -47,11 +47,13 @@ #include #include #include +#include class UavcanEscController { public: UavcanEscController(uavcan::INode& node); + ~UavcanEscController(); int init(); @@ -96,4 +98,10 @@ private: */ bool _armed = false; uavcan::equipment::esc::Status _states[MAX_ESCS]; + + /* + * Perf counters + */ + perf_counter_t _perfcnt_invalid_input = perf_alloc(PC_COUNT, "uavcan_esc_invalid_input"); + perf_counter_t _perfcnt_scaling_error = perf_alloc(PC_COUNT, "uavcan_esc_scaling_error"); }; -- cgit v1.2.3 From dae9b48462bc851ee61d6d18ff2b5697dddf620b Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 Jul 2014 02:31:05 +0400 Subject: Renamed OUTPUT_MODE: can --> uavcan_esc --- ROMFS/px4fmu_common/init.d/4012_quad_x_can | 2 +- ROMFS/px4fmu_common/init.d/rc.interface | 2 +- ROMFS/px4fmu_common/init.d/rcS | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/4012_quad_x_can b/ROMFS/px4fmu_common/init.d/4012_quad_x_can index 471ac54b4..8c5a4fbf2 100644 --- a/ROMFS/px4fmu_common/init.d/4012_quad_x_can +++ b/ROMFS/px4fmu_common/init.d/4012_quad_x_can @@ -24,4 +24,4 @@ then param set MC_YAWRATE_D 0.0 fi -set OUTPUT_MODE can +set OUTPUT_MODE uavcan_esc diff --git a/ROMFS/px4fmu_common/init.d/rc.interface b/ROMFS/px4fmu_common/init.d/rc.interface index da4c73470..1de0abb58 100644 --- a/ROMFS/px4fmu_common/init.d/rc.interface +++ b/ROMFS/px4fmu_common/init.d/rc.interface @@ -25,7 +25,7 @@ then set OUTPUT_DEV /dev/pwm_output fi - if [ $OUTPUT_MODE == can ] + if [ $OUTPUT_MODE == uavcan_esc ] then set OUTPUT_DEV /dev/uavcan/esc fi diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index c95016ace..975cb6d1d 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -292,7 +292,7 @@ then # If OUTPUT_MODE == none then something is wrong with setup and we shouldn't try to enable output if [ $OUTPUT_MODE != none ] then - if [ $OUTPUT_MODE == can ] + if [ $OUTPUT_MODE == uavcan_esc ] then if uavcan start 1 then @@ -302,7 +302,7 @@ then fi fi - if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == can ] + if [ $OUTPUT_MODE == io -o $OUTPUT_MODE == uavcan_esc ] then echo "[init] Use PX4IO PWM as primary output" if px4io start -- cgit v1.2.3 From b8ba6400f26e573236d60929283c673fb620f28e Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 6 Jul 2014 16:04:30 -0700 Subject: More logging --- src/modules/mavlink/mavlink_ftp.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index b2e6e9d30..2da381a2d 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -210,7 +210,7 @@ MavlinkFTP::_workList(Request *req) return kErrNotDir; } - printf("FTP: list %s\n", dirPath); + printf("FTP: list %s offset %d\n", dirPath, hdr->offset); ErrorCode errorCode = kErrNone; struct dirent entry, *result = nullptr; @@ -258,7 +258,7 @@ MavlinkFTP::_workList(Request *req) // copy the name, which we know will fit strcpy((char *)&hdr->data[offset], entry.d_name); - printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset]); + printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]); offset += strlen(entry.d_name) + 1; } -- cgit v1.2.3 From 2a79689224a381cf777c555d330f0a2aca8e3d9a Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 6 Jul 2014 16:51:06 -0700 Subject: Fix unused variable warnings --- src/modules/commander/commander.cpp | 4 ++-- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 7 +------ src/modules/fw_pos_control_l1/mtecs/mTecs.cpp | 2 +- src/modules/mavlink/mavlink_ftp.cpp | 2 +- src/systemcmds/tests/test_mathlib.cpp | 3 +++ 5 files changed, 8 insertions(+), 10 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index f83c1caf8..3d4a297f7 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -773,7 +773,7 @@ int commander_thread_main(int argc, char *argv[]) bool updated = false; - bool rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd)); + rc_calibration_check(mavlink_fd); /* Subscribe to safety topic */ int safety_sub = orb_subscribe(ORB_ID(safety)); @@ -934,7 +934,7 @@ int commander_thread_main(int argc, char *argv[]) status_changed = true; /* re-check RC calibration */ - rc_calibration_ok = (OK == rc_calibration_check(mavlink_fd)); + rc_calibration_check(mavlink_fd); } /* navigation parameters */ diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 3e835cf81..3d6c62434 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -807,12 +807,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float eas2tas = 1.0f; // XXX calculate actual number based on current measurements - // XXX re-visit - float baro_altitude = _global_pos.alt; - /* filter speed and altitude for controller */ math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2); - math::Vector<3> accel_earth = _R_nb * accel_body; float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt; @@ -945,8 +941,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float airspeed_land = 1.3f * _parameters.airspeed_min; float airspeed_approach = 1.3f * _parameters.airspeed_min; - /* Calculate distance (to landing waypoint) and altitude of last ordinary waypoint L */ - float L_wp_distance = get_distance_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1)); + /* Calculate altitude of last ordinary waypoint L */ float L_altitude_rel = _pos_sp_triplet.previous.valid ? _pos_sp_triplet.previous.alt - _pos_sp_triplet.current.alt : 0.0f; float bearing_airplane_currwp = get_bearing_to_next_waypoint(current_position(0), current_position(1), curr_wp(0), curr_wp(1)); diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp index fc0a2551c..2e37d166e 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp @@ -220,7 +220,7 @@ int mTecs::updateFlightPathAngleAcceleration(float flightPathAngle, float flight /* Apply overrride given by the limitOverride argument (this is used for limits which are not given by * parameters such as pitch limits with takeoff waypoints or throttle limits when the launchdetector * is running) */ - bool limitApplied = limitOverride.applyOverride(*outputLimiterThrottle, *outputLimiterPitch); + limitOverride.applyOverride(*outputLimiterThrottle, *outputLimiterPitch); /* Write part of the status message */ _status.flightPathAngleSp = flightPathAngleSp; diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index ca846a465..55a472bf6 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -346,7 +346,7 @@ MavlinkFTP::_workWrite(Request *req) MavlinkFTP::ErrorCode MavlinkFTP::_workRemove(Request *req) { - auto hdr = req->header(); + //auto hdr = req->header(); // for now, send error reply return kErrPerm; diff --git a/src/systemcmds/tests/test_mathlib.cpp b/src/systemcmds/tests/test_mathlib.cpp index 00c649c75..df3ddb966 100644 --- a/src/systemcmds/tests/test_mathlib.cpp +++ b/src/systemcmds/tests/test_mathlib.cpp @@ -96,8 +96,11 @@ int test_mathlib(int argc, char *argv[]) TEST_OP("Vector<3> %% Vector<3>", v1 % v2); TEST_OP("Vector<3> length", v1.length()); TEST_OP("Vector<3> length squared", v1.length_squared()); +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wunused-variable" TEST_OP("Vector<3> element read", volatile float a = v1(0)); TEST_OP("Vector<3> element read direct", volatile float a = v1.data[0]); +#pragma GCC diagnostic pop TEST_OP("Vector<3> element write", v1(0) = 1.0f); TEST_OP("Vector<3> element write direct", v1.data[0] = 1.0f); } -- cgit v1.2.3 From 72a531b018f0089c89ed40261969555fd282e459 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 Jul 2014 15:07:37 +0400 Subject: Fixed UAVCAN GNSS bridge - EPV computation, catching up with the new GPS ORB topic --- src/modules/uavcan/gnss_receiver.cpp | 28 ++++++++++++++-------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/src/modules/uavcan/gnss_receiver.cpp b/src/modules/uavcan/gnss_receiver.cpp index 3e98bdf14..debba9fee 100644 --- a/src/modules/uavcan/gnss_receiver.cpp +++ b/src/modules/uavcan/gnss_receiver.cpp @@ -85,13 +85,18 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure 0) ? sqrtf(horizontal_pos_variance) : -1.0F; + + // Vertical position uncertainty + _report.epv = (pos_cov[8] > 0) ? sqrtf(pos_cov[8]) : -1.0F; } else { - _report.p_variance_m = -1.0; - _report.eph_m = -1.0; + _report.eph = -1.0F; + _report.epv = -1.0F; } if (valid_velocity_covariance) { @@ -118,12 +123,9 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure 0) { orb_publish(ORB_ID(vehicle_gps_position), _report_pub, &_report); -- cgit v1.2.3 From 664795c9db9a0d938cbe7221aed87755ca8de7bf Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Mon, 7 Jul 2014 15:47:40 +0400 Subject: UAVCAN GNSS - using GNSS time to initialize the field time_gps_usec --- src/modules/uavcan/gnss_receiver.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uavcan/gnss_receiver.cpp b/src/modules/uavcan/gnss_receiver.cpp index debba9fee..ba1fe5e49 100644 --- a/src/modules/uavcan/gnss_receiver.cpp +++ b/src/modules/uavcan/gnss_receiver.cpp @@ -139,7 +139,7 @@ void UavcanGnssReceiver::gnss_fix_sub_cb(const uavcan::ReceivedDataStructure Date: Mon, 7 Jul 2014 14:59:57 +0200 Subject: change mavlink submodule url --- .gitmodules | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.gitmodules b/.gitmodules index 946a1fdcf..c5116c1cb 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,3 +1,3 @@ [submodule "mavlink/include/mavlink/v1.0"] path = mavlink/include/mavlink/v1.0 - url = git@github.com:mavlink/c_library.git + url = https://github.com/mavlink/c_library.git -- cgit v1.2.3 From 530e70bc4697a7e436a4cc9557ce38e139ee2795 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 7 Jul 2014 15:13:27 +0200 Subject: navigator: forgot to fix conflicts --- src/modules/navigator/navigator.h | 2 +- src/modules/navigator/navigator_main.cpp | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index ae2e01c8c..bf6e2ea0e 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -113,7 +113,7 @@ public: struct vehicle_control_mode_s* get_control_mode() { return &_control_mode; } struct vehicle_global_position_s* get_global_position() { return &_global_pos; } struct home_position_s* get_home_position() { return &_home_pos; } - + struct position_setpoint_triplet_s* get_position_setpoint_triplet() { return &_pos_sp_triplet; } int get_onboard_mission_sub() { return _onboard_mission_sub; } int get_offboard_mission_sub() { return _offboard_mission_sub; } int get_offboard_control_sp_sub() { return _offboard_control_sp_sub; } diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index c959bf891..1a5ba4c1a 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -124,7 +124,6 @@ Navigator::Navigator() : _loiter(this, "LOI"), _rtl(this, "RTL"), _offboard(this, "OFF"), - _update_triplet_updated(false), _param_loiter_radius(this, "LOITER_RAD"), _param_acceptance_radius(this, "ACC_RAD") { -- cgit v1.2.3 From 29bf1fe6fa40968f1cda53c3aa9f4dad3ec25ebb Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 7 Jul 2014 15:18:12 +0200 Subject: dataman: added macro for offboard storage selection --- src/modules/dataman/dataman.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/dataman/dataman.h b/src/modules/dataman/dataman.h index dbace21ef..d625bf985 100644 --- a/src/modules/dataman/dataman.h +++ b/src/modules/dataman/dataman.h @@ -57,6 +57,8 @@ extern "C" { DM_KEY_NUM_KEYS /* Total number of item types defined */ } dm_item_t; + #define DM_KEY_WAYPOINTS_OFFBOARD(_id) (_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1) + /** The maximum number of instances for each item type */ enum { DM_KEY_SAFE_POINTS_MAX = 8, -- cgit v1.2.3 From a29f7cad395ce53b74500a0dc03214186c679378 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 7 Jul 2014 15:18:54 +0200 Subject: navigator: reject mission if the first waypoint is too far from home --- src/modules/navigator/mission.cpp | 69 +++++++++++++++++++++++++++++++++- src/modules/navigator/mission.h | 10 ++++- src/modules/navigator/mission_params.c | 13 ++++++- 3 files changed, 89 insertions(+), 3 deletions(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 291e2edeb..53f0724cd 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -61,6 +61,7 @@ Mission::Mission(Navigator *navigator, const char *name) : MissionBlock(navigator, name), _param_onboard_enabled(this, "ONBOARD_EN"), _param_takeoff_alt(this, "TAKEOFF_ALT"), + _param_dist_1wp(this, "DIST_1WP"), _onboard_mission({0}), _offboard_mission({0}), _current_onboard_mission_index(-1), @@ -69,8 +70,10 @@ Mission::Mission(Navigator *navigator, const char *name) : _mission_result({0}), _mission_type(MISSION_TYPE_NONE), _inited(false), + _dist_1wp_ok(false), _need_takeoff(true), _takeoff(false) + { /* load initial params */ updateParams(); @@ -246,6 +249,70 @@ Mission::advance_mission() } } +bool +Mission::check_dist_1wp() +{ + if (_dist_1wp_ok) { + /* always return true after at least one successful check */ + return true; + } + + /* check if first waypoint is not too far from home */ + bool mission_valid = false; + if (_param_dist_1wp.get() > 0.0f) { + if (_navigator->get_vstatus()->condition_home_position_valid) { + struct mission_item_s mission_item; + + /* find first waypoint (with lat/lon) item in datamanager */ + for (int i = 0; i < _offboard_mission.count; i++) { + if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id), i, + &mission_item, sizeof(mission_item_s)) == sizeof(mission_item_s)) { + + /* check only items with valid lat/lon */ + if ( mission_item.nav_cmd == NAV_CMD_WAYPOINT || + mission_item.nav_cmd == NAV_CMD_LOITER_TIME_LIMIT || + mission_item.nav_cmd == NAV_CMD_LOITER_TURN_COUNT || + mission_item.nav_cmd == NAV_CMD_LOITER_UNLIMITED || + mission_item.nav_cmd == NAV_CMD_TAKEOFF || + mission_item.nav_cmd == NAV_CMD_PATHPLANNING) { + + /* check distance from home to item */ + float dist_to_1wp = get_distance_to_next_waypoint( + mission_item.lat, mission_item.lon, + _navigator->get_home_position()->lat, _navigator->get_home_position()->lon); + + if (dist_to_1wp < _param_dist_1wp.get()) { + _dist_1wp_ok = true; + return true; + + } else { + /* item is too far from home */ + mavlink_log_info(_navigator->get_mavlink_fd(), "first wp is too far from home: %.1fm > %.1fm", dist_to_1wp, _param_dist_1wp.get()); + return false; + } + } + + } else { + /* error reading, mission is invalid */ + mavlink_log_info(_navigator->get_mavlink_fd(), "error reading offboard mission"); + return false; + } + } + + /* no waypoints found in mission, then we will not fly far away */ + _dist_1wp_ok = true; + return true; + + } else { + mavlink_log_info(_navigator->get_mavlink_fd(), "no home position"); + return false; + } + + } else { + return true; + } +} + void Mission::set_mission_items() { @@ -266,7 +333,7 @@ Mission::set_mission_items() _mission_type = MISSION_TYPE_ONBOARD; /* try setting offboard mission item */ - } else if (read_mission_item(false, true, &_mission_item)) { + } else if (check_dist_1wp() && read_mission_item(false, true, &_mission_item)) { /* if mission type changed, notify */ if (_mission_type != MISSION_TYPE_OFFBOARD) { mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: offboard mission running"); diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index 40629b1b2..4da6a1155 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -91,6 +91,12 @@ private: */ void advance_mission(); + /** + * Check distance to first waypoint (with lat/lon) + * @return true only if it's not too far from home (< MIS_DIST_1WP) + */ + bool check_dist_1wp(); + /** * Set new mission items */ @@ -127,8 +133,9 @@ private: */ void publish_mission_result(); - control::BlockParamFloat _param_onboard_enabled; + control::BlockParamInt _param_onboard_enabled; control::BlockParamFloat _param_takeoff_alt; + control::BlockParamFloat _param_dist_1wp; struct mission_s _onboard_mission; struct mission_s _offboard_mission; @@ -148,6 +155,7 @@ private: } _mission_type; bool _inited; + bool _dist_1wp_ok; MissionFeasibilityChecker missionFeasiblityChecker; /**< class that checks if a mission is feasible */ }; diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c index 8692328db..5cb3782c9 100644 --- a/src/modules/navigator/mission_params.c +++ b/src/modules/navigator/mission_params.c @@ -58,7 +58,6 @@ */ PARAM_DEFINE_FLOAT(MIS_TAKEOFF_ALT, 10.0f); - /** * Enable onboard mission * @@ -67,3 +66,15 @@ PARAM_DEFINE_FLOAT(MIS_TAKEOFF_ALT, 10.0f); * @group Mission */ PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 0); + +/** + * Maximal horizontal distance from home to first waypoint + * + * Failsafe check to prevent running mission stored from previous flight on new place. + * Value < 0 means that check disabled. + * + * @min -1 + * @max 200 + * @group Mission + */ +PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 50); -- cgit v1.2.3 From 68dbf0057a3a80713f79a10669128b7bc9b5cebb Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 7 Jul 2014 15:25:32 +0200 Subject: add mavlink submodule check script The script checks if the mavlink submodule is up to date --- Tools/check_submodules.sh | 10 ++++++++++ 1 file changed, 10 insertions(+) create mode 100755 Tools/check_submodules.sh diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh new file mode 100755 index 000000000..52ea7a146 --- /dev/null +++ b/Tools/check_submodules.sh @@ -0,0 +1,10 @@ +#!/bin/sh +STATUSRETVAL=$(git status --porcelain | grep -i "M mavlink/include/mavlink/v1.0") +if [ "$STATUSRETVAL" == "" ]; then + echo "checked mavlink submodule, correct version found" +else + echo "mavlink sub repo not at correct version. Try 'git submodule update'" + exit 1 +fi + +exit 0 -- cgit v1.2.3 From d79a80e8bed19ebbff333c244c3c90bae39c9181 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 7 Jul 2014 16:57:39 +0200 Subject: really remove mavlink folder --- mavlink/include/mavlink/config.h | 1 - mavlink/include/mavlink/v1.0 | 1 - mavlink/lib/pkgconfig/mavlink.pc | 7 - .../share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc | 5431 -------------------- mavlink/share/pyshared/pymavlink/.gitignore | 13 - .../pyshared/pymavlink/APM_Mavtest/APM_Mavtest.pde | 55 - mavlink/share/pyshared/pymavlink/README.txt | 4 - .../pyshared/pymavlink/examples/apmsetrate.py | 67 - .../share/pyshared/pymavlink/examples/bwtest.py | 58 - .../pyshared/pymavlink/examples/flightmodes.py | 52 - .../pyshared/pymavlink/examples/flighttime.py | 59 - .../share/pyshared/pymavlink/examples/gpslock.py | 68 - .../share/pyshared/pymavlink/examples/magfit.py | 138 - .../pyshared/pymavlink/examples/magfit_delta.py | 145 - .../pyshared/pymavlink/examples/magfit_gps.py | 159 - .../share/pyshared/pymavlink/examples/magtest.py | 120 - .../share/pyshared/pymavlink/examples/mavgraph.py | 196 - .../pyshared/pymavlink/examples/mavlogdump.py | 67 - .../share/pyshared/pymavlink/examples/mavparms.py | 48 - .../share/pyshared/pymavlink/examples/mavtest.py | 41 - .../share/pyshared/pymavlink/examples/mavtester.py | 43 - .../share/pyshared/pymavlink/examples/mavtogpx.py | 83 - .../share/pyshared/pymavlink/examples/rotmat.py | 269 - .../share/pyshared/pymavlink/examples/sigloss.py | 57 - .../share/pyshared/pymavlink/examples/wptogpx.py | 69 - mavlink/share/pyshared/pymavlink/fgFDM.py | 209 - .../share/pyshared/pymavlink/generator/.gitignore | 1 - .../pymavlink/generator/C/include_v0.9/checksum.h | 89 - .../generator/C/include_v0.9/mavlink_helpers.h | 488 -- .../generator/C/include_v0.9/mavlink_types.h | 300 -- .../pymavlink/generator/C/include_v0.9/protocol.h | 319 -- .../generator/C/include_v0.9/test/mavlink.h | 27 - .../C/include_v0.9/test/mavlink_msg_test_types.h | 610 --- .../pymavlink/generator/C/include_v0.9/test/test.h | 53 - .../generator/C/include_v0.9/test/testsuite.h | 120 - .../generator/C/include_v0.9/test/version.h | 12 - .../pymavlink/generator/C/include_v1.0/checksum.h | 89 - .../generator/C/include_v1.0/mavlink_helpers.h | 507 -- .../C/include_v1.0/mavlink_protobuf_manager.hpp | 377 -- .../generator/C/include_v1.0/mavlink_types.h | 158 - .../generator/C/include_v1.0/pixhawk/pixhawk.pb.h | 3663 ------------- .../pymavlink/generator/C/include_v1.0/protocol.h | 322 -- .../generator/C/include_v1.0/test/mavlink.h | 27 - .../C/include_v1.0/test/mavlink_msg_test_types.h | 610 --- .../pymavlink/generator/C/include_v1.0/test/test.h | 53 - .../generator/C/include_v1.0/test/testsuite.h | 120 - .../generator/C/include_v1.0/test/version.h | 12 - .../generator/C/src_v1.0/pixhawk/pixhawk.pb.cc | 5431 -------------------- .../pymavlink/generator/C/test/posix/.gitignore | 3 - .../pymavlink/generator/C/test/posix/testmav.c | 159 - .../pymavlink/generator/C/test/windows/stdafx.cpp | 8 - .../pymavlink/generator/C/test/windows/stdafx.h | 15 - .../pymavlink/generator/C/test/windows/targetver.h | 8 - .../pymavlink/generator/C/test/windows/testmav.cpp | 154 - .../pymavlink/generator/gen_MatrixPilot.py | 93 - .../share/pyshared/pymavlink/generator/gen_all.py | 44 - .../share/pyshared/pymavlink/generator/gen_all.sh | 12 - .../share/pyshared/pymavlink/generator/mavgen.py | 82 - .../share/pyshared/pymavlink/generator/mavgen_c.py | 581 --- .../pyshared/pymavlink/generator/mavgen_python.py | 455 -- .../share/pyshared/pymavlink/generator/mavparse.py | 372 -- .../pyshared/pymavlink/generator/mavtemplate.py | 121 - .../pyshared/pymavlink/generator/mavtestgen.py | 142 - mavlink/share/pyshared/pymavlink/mavextra.py | 154 - mavlink/share/pyshared/pymavlink/mavlink.py | 4930 ------------------ mavlink/share/pyshared/pymavlink/mavlinkv10.py | 5394 ------------------- mavlink/share/pyshared/pymavlink/mavutil.py | 678 --- mavlink/share/pyshared/pymavlink/mavwp.py | 200 - mavlink/share/pyshared/pymavlink/scanwin32.py | 236 - .../pyshared/pymavlink/tools/images/gtk-quit.gif | Bin 1049 -> 0 bytes .../tools/images/media-playback-pause.gif | Bin 314 -> 0 bytes .../tools/images/media-playback-start.gif | Bin 308 -> 0 bytes .../pymavlink/tools/images/media-playback-stop.gif | Bin 305 -> 0 bytes .../pymavlink/tools/images/media-seek-backward.gif | Bin 319 -> 0 bytes .../pymavlink/tools/images/media-seek-forward.gif | Bin 322 -> 0 bytes .../pyshared/pymavlink/tools/images/player_end.gif | Bin 555 -> 0 bytes .../share/pyshared/pymavlink/tools/mavplayback.py | 246 - 77 files changed, 34935 deletions(-) delete mode 100644 mavlink/include/mavlink/config.h delete mode 160000 mavlink/include/mavlink/v1.0 delete mode 100644 mavlink/lib/pkgconfig/mavlink.pc delete mode 100644 mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc delete mode 100644 mavlink/share/pyshared/pymavlink/.gitignore delete mode 100644 mavlink/share/pyshared/pymavlink/APM_Mavtest/APM_Mavtest.pde delete mode 100644 mavlink/share/pyshared/pymavlink/README.txt delete mode 100644 mavlink/share/pyshared/pymavlink/examples/apmsetrate.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/bwtest.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/flightmodes.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/flighttime.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/gpslock.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/magfit.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/magfit_delta.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/magfit_gps.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/magtest.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/mavgraph.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/mavlogdump.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/mavparms.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/mavtest.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/mavtester.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/mavtogpx.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/rotmat.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/sigloss.py delete mode 100644 mavlink/share/pyshared/pymavlink/examples/wptogpx.py delete mode 100644 mavlink/share/pyshared/pymavlink/fgFDM.py delete mode 100644 mavlink/share/pyshared/pymavlink/generator/.gitignore delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/mavlink_msg_test_types.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/version.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/checksum.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/mavlink_msg_test_types.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/version.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/src_v1.0/pixhawk/pixhawk.pb.cc delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h delete mode 100644 mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp delete mode 100644 mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py delete mode 100644 mavlink/share/pyshared/pymavlink/generator/gen_all.py delete mode 100644 mavlink/share/pyshared/pymavlink/generator/gen_all.sh delete mode 100644 mavlink/share/pyshared/pymavlink/generator/mavgen.py delete mode 100644 mavlink/share/pyshared/pymavlink/generator/mavgen_c.py delete mode 100644 mavlink/share/pyshared/pymavlink/generator/mavgen_python.py delete mode 100644 mavlink/share/pyshared/pymavlink/generator/mavparse.py delete mode 100644 mavlink/share/pyshared/pymavlink/generator/mavtemplate.py delete mode 100644 mavlink/share/pyshared/pymavlink/generator/mavtestgen.py delete mode 100644 mavlink/share/pyshared/pymavlink/mavextra.py delete mode 100644 mavlink/share/pyshared/pymavlink/mavlink.py delete mode 100644 mavlink/share/pyshared/pymavlink/mavlinkv10.py delete mode 100644 mavlink/share/pyshared/pymavlink/mavutil.py delete mode 100644 mavlink/share/pyshared/pymavlink/mavwp.py delete mode 100644 mavlink/share/pyshared/pymavlink/scanwin32.py delete mode 100644 mavlink/share/pyshared/pymavlink/tools/images/gtk-quit.gif delete mode 100644 mavlink/share/pyshared/pymavlink/tools/images/media-playback-pause.gif delete mode 100644 mavlink/share/pyshared/pymavlink/tools/images/media-playback-start.gif delete mode 100644 mavlink/share/pyshared/pymavlink/tools/images/media-playback-stop.gif delete mode 100644 mavlink/share/pyshared/pymavlink/tools/images/media-seek-backward.gif delete mode 100644 mavlink/share/pyshared/pymavlink/tools/images/media-seek-forward.gif delete mode 100644 mavlink/share/pyshared/pymavlink/tools/images/player_end.gif delete mode 100644 mavlink/share/pyshared/pymavlink/tools/mavplayback.py diff --git a/mavlink/include/mavlink/config.h b/mavlink/include/mavlink/config.h deleted file mode 100644 index db7db0d7d..000000000 --- a/mavlink/include/mavlink/config.h +++ /dev/null @@ -1 +0,0 @@ -#define MAVLINK_VERSION "1.0.7" diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 deleted file mode 160000 index 45a71d656..000000000 --- a/mavlink/include/mavlink/v1.0 +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 45a71d6564bc5c47ed97d620089e17ca48bab73f diff --git a/mavlink/lib/pkgconfig/mavlink.pc b/mavlink/lib/pkgconfig/mavlink.pc deleted file mode 100644 index be9036495..000000000 --- a/mavlink/lib/pkgconfig/mavlink.pc +++ /dev/null @@ -1,7 +0,0 @@ -prefix=/ -exec_prefix=/ - -Name: mavlink -Description: -Version: -Cflags: -I//include/mavlink diff --git a/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc b/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc deleted file mode 100644 index e984f512a..000000000 --- a/mavlink/share/mavlink/src/v1.0/pixhawk/pixhawk.pb.cc +++ /dev/null @@ -1,5431 +0,0 @@ -// Generated by the protocol buffer compiler. DO NOT EDIT! - -#define INTERNAL_SUPPRESS_PROTOBUF_FIELD_DEPRECATION -#include "pixhawk.pb.h" - -#include - -#include -#include -#include -#include -#include -#include -// @@protoc_insertion_point(includes) - -namespace px { - -namespace { - -const ::google::protobuf::Descriptor* HeaderInfo_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - HeaderInfo_reflection_ = NULL; -const ::google::protobuf::Descriptor* GLOverlay_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - GLOverlay_reflection_ = NULL; -const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor_ = NULL; -const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor_ = NULL; -const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor_ = NULL; -const ::google::protobuf::Descriptor* Obstacle_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - Obstacle_reflection_ = NULL; -const ::google::protobuf::Descriptor* ObstacleList_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - ObstacleList_reflection_ = NULL; -const ::google::protobuf::Descriptor* ObstacleMap_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - ObstacleMap_reflection_ = NULL; -const ::google::protobuf::Descriptor* Path_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - Path_reflection_ = NULL; -const ::google::protobuf::Descriptor* PointCloudXYZI_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - PointCloudXYZI_reflection_ = NULL; -const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - PointCloudXYZI_PointXYZI_reflection_ = NULL; -const ::google::protobuf::Descriptor* PointCloudXYZRGB_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - PointCloudXYZRGB_reflection_ = NULL; -const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - PointCloudXYZRGB_PointXYZRGB_reflection_ = NULL; -const ::google::protobuf::Descriptor* RGBDImage_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - RGBDImage_reflection_ = NULL; -const ::google::protobuf::Descriptor* Waypoint_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - Waypoint_reflection_ = NULL; - -} // namespace - - -void protobuf_AssignDesc_pixhawk_2eproto() { - protobuf_AddDesc_pixhawk_2eproto(); - const ::google::protobuf::FileDescriptor* file = - ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName( - "pixhawk.proto"); - GOOGLE_CHECK(file != NULL); - HeaderInfo_descriptor_ = file->message_type(0); - static const int HeaderInfo_offsets_[3] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_sysid_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_compid_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, timestamp_), - }; - HeaderInfo_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - HeaderInfo_descriptor_, - HeaderInfo::default_instance_, - HeaderInfo_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(HeaderInfo)); - GLOverlay_descriptor_ = file->message_type(1); - static const int GLOverlay_offsets_[7] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, name_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, coordinateframetype_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, data_), - }; - GLOverlay_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - GLOverlay_descriptor_, - GLOverlay::default_instance_, - GLOverlay_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(GLOverlay)); - GLOverlay_CoordinateFrameType_descriptor_ = GLOverlay_descriptor_->enum_type(0); - GLOverlay_Mode_descriptor_ = GLOverlay_descriptor_->enum_type(1); - GLOverlay_Identifier_descriptor_ = GLOverlay_descriptor_->enum_type(2); - Obstacle_descriptor_ = file->message_type(2); - static const int Obstacle_offsets_[6] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, length_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, width_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, height_), - }; - Obstacle_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - Obstacle_descriptor_, - Obstacle::default_instance_, - Obstacle_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(Obstacle)); - ObstacleList_descriptor_ = file->message_type(3); - static const int ObstacleList_offsets_[2] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, obstacles_), - }; - ObstacleList_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - ObstacleList_descriptor_, - ObstacleList::default_instance_, - ObstacleList_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(ObstacleList)); - ObstacleMap_descriptor_ = file->message_type(4); - static const int ObstacleMap_offsets_[10] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, type_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, resolution_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, rows_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, cols_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapr0_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapc0_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayr0_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayc0_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, data_), - }; - ObstacleMap_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - ObstacleMap_descriptor_, - ObstacleMap::default_instance_, - ObstacleMap_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(ObstacleMap)); - Path_descriptor_ = file->message_type(5); - static const int Path_offsets_[2] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, waypoints_), - }; - Path_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - Path_descriptor_, - Path::default_instance_, - Path_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(Path)); - PointCloudXYZI_descriptor_ = file->message_type(6); - static const int PointCloudXYZI_offsets_[2] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, points_), - }; - PointCloudXYZI_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - PointCloudXYZI_descriptor_, - PointCloudXYZI::default_instance_, - PointCloudXYZI_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(PointCloudXYZI)); - PointCloudXYZI_PointXYZI_descriptor_ = PointCloudXYZI_descriptor_->nested_type(0); - static const int PointCloudXYZI_PointXYZI_offsets_[4] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, intensity_), - }; - PointCloudXYZI_PointXYZI_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - PointCloudXYZI_PointXYZI_descriptor_, - PointCloudXYZI_PointXYZI::default_instance_, - PointCloudXYZI_PointXYZI_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(PointCloudXYZI_PointXYZI)); - PointCloudXYZRGB_descriptor_ = file->message_type(7); - static const int PointCloudXYZRGB_offsets_[2] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, points_), - }; - PointCloudXYZRGB_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - PointCloudXYZRGB_descriptor_, - PointCloudXYZRGB::default_instance_, - PointCloudXYZRGB_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(PointCloudXYZRGB)); - PointCloudXYZRGB_PointXYZRGB_descriptor_ = PointCloudXYZRGB_descriptor_->nested_type(0); - static const int PointCloudXYZRGB_PointXYZRGB_offsets_[4] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, rgb_), - }; - PointCloudXYZRGB_PointXYZRGB_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - PointCloudXYZRGB_PointXYZRGB_descriptor_, - PointCloudXYZRGB_PointXYZRGB::default_instance_, - PointCloudXYZRGB_PointXYZRGB_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(PointCloudXYZRGB_PointXYZRGB)); - RGBDImage_descriptor_ = file->message_type(8); - static const int RGBDImage_offsets_[21] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, cols_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, rows_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step1_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type1_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata1_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step2_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type2_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata2_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_config_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_type_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, roll_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, pitch_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, yaw_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lon_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lat_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, alt_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_matrix_), - }; - RGBDImage_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - RGBDImage_descriptor_, - RGBDImage::default_instance_, - RGBDImage_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(RGBDImage)); - Waypoint_descriptor_ = file->message_type(9); - static const int Waypoint_offsets_[6] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, roll_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, pitch_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, yaw_), - }; - Waypoint_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - Waypoint_descriptor_, - Waypoint::default_instance_, - Waypoint_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(Waypoint)); -} - -namespace { - -GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_); -inline void protobuf_AssignDescriptorsOnce() { - ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_, - &protobuf_AssignDesc_pixhawk_2eproto); -} - -void protobuf_RegisterTypes(const ::std::string&) { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - HeaderInfo_descriptor_, &HeaderInfo::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - GLOverlay_descriptor_, &GLOverlay::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - Obstacle_descriptor_, &Obstacle::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - ObstacleList_descriptor_, &ObstacleList::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - ObstacleMap_descriptor_, &ObstacleMap::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - Path_descriptor_, &Path::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - PointCloudXYZI_descriptor_, &PointCloudXYZI::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - PointCloudXYZI_PointXYZI_descriptor_, &PointCloudXYZI_PointXYZI::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - PointCloudXYZRGB_descriptor_, &PointCloudXYZRGB::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - PointCloudXYZRGB_PointXYZRGB_descriptor_, &PointCloudXYZRGB_PointXYZRGB::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - RGBDImage_descriptor_, &RGBDImage::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - Waypoint_descriptor_, &Waypoint::default_instance()); -} - -} // namespace - -void protobuf_ShutdownFile_pixhawk_2eproto() { - delete HeaderInfo::default_instance_; - delete HeaderInfo_reflection_; - delete GLOverlay::default_instance_; - delete GLOverlay_reflection_; - delete Obstacle::default_instance_; - delete Obstacle_reflection_; - delete ObstacleList::default_instance_; - delete ObstacleList_reflection_; - delete ObstacleMap::default_instance_; - delete ObstacleMap_reflection_; - delete Path::default_instance_; - delete Path_reflection_; - delete PointCloudXYZI::default_instance_; - delete PointCloudXYZI_reflection_; - delete PointCloudXYZI_PointXYZI::default_instance_; - delete PointCloudXYZI_PointXYZI_reflection_; - delete PointCloudXYZRGB::default_instance_; - delete PointCloudXYZRGB_reflection_; - delete PointCloudXYZRGB_PointXYZRGB::default_instance_; - delete PointCloudXYZRGB_PointXYZRGB_reflection_; - delete RGBDImage::default_instance_; - delete RGBDImage_reflection_; - delete Waypoint::default_instance_; - delete Waypoint_reflection_; -} - -void protobuf_AddDesc_pixhawk_2eproto() { - static bool already_here = false; - if (already_here) return; - already_here = true; - GOOGLE_PROTOBUF_VERIFY_VERSION; - - ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( - "\n\rpixhawk.proto\022\002px\"L\n\nHeaderInfo\022\024\n\014sou" - "rce_sysid\030\001 \002(\005\022\025\n\rsource_compid\030\002 \002(\005\022\021" - "\n\ttimestamp\030\003 \002(\001\"\377\004\n\tGLOverlay\022\036\n\006heade" - "r\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004name\030\002 \001(\t\022>\n" - "\023coordinateFrameType\030\003 \001(\0162!.px.GLOverla" - "y.CoordinateFrameType\022\020\n\010origin_x\030\004 \001(\001\022" - "\020\n\010origin_y\030\005 \001(\001\022\020\n\010origin_z\030\006 \001(\001\022\014\n\004d" - "ata\030\007 \001(\014\",\n\023CoordinateFrameType\022\n\n\006GLOB" - "AL\020\000\022\t\n\005LOCAL\020\001\"\333\001\n\004Mode\022\n\n\006POINTS\020\000\022\t\n\005" - "LINES\020\001\022\016\n\nLINE_STRIP\020\002\022\r\n\tLINE_LOOP\020\003\022\r" - "\n\tTRIANGLES\020\004\022\022\n\016TRIANGLE_STRIP\020\005\022\020\n\014TRI" - "ANGLE_FAN\020\006\022\t\n\005QUADS\020\007\022\016\n\nQUAD_STRIP\020\010\022\013" - "\n\007POLYGON\020\t\022\020\n\014SOLID_CIRCLE\020\n\022\017\n\013WIRE_CI" - "RCLE\020\013\022\016\n\nSOLID_CUBE\020\014\022\r\n\tWIRE_CUBE\020\r\"\263\001" - "\n\nIdentifier\022\007\n\003END\020\016\022\014\n\010VERTEX2F\020\017\022\014\n\010V" - "ERTEX3F\020\020\022\013\n\007ROTATEF\020\021\022\016\n\nTRANSLATEF\020\022\022\n" - "\n\006SCALEF\020\023\022\017\n\013PUSH_MATRIX\020\024\022\016\n\nPOP_MATRI" - "X\020\025\022\013\n\007COLOR3F\020\026\022\013\n\007COLOR4F\020\027\022\r\n\tPOINTSI" - "ZE\020\030\022\r\n\tLINEWIDTH\020\031\"Z\n\010Obstacle\022\t\n\001x\030\001 \001" - "(\002\022\t\n\001y\030\002 \001(\002\022\t\n\001z\030\003 \001(\002\022\016\n\006length\030\004 \001(\002" - "\022\r\n\005width\030\005 \001(\002\022\016\n\006height\030\006 \001(\002\"O\n\014Obsta" - "cleList\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo\022" - "\037\n\tobstacles\030\002 \003(\0132\014.px.Obstacle\"\271\001\n\013Obs" - "tacleMap\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo" - "\022\014\n\004type\030\002 \002(\005\022\022\n\nresolution\030\003 \001(\002\022\014\n\004ro" - "ws\030\004 \001(\005\022\014\n\004cols\030\005 \001(\005\022\r\n\005mapR0\030\006 \001(\005\022\r\n" - "\005mapC0\030\007 \001(\005\022\017\n\007arrayR0\030\010 \001(\005\022\017\n\007arrayC0" - "\030\t \001(\005\022\014\n\004data\030\n \001(\014\"G\n\004Path\022\036\n\006header\030\001" - " \002(\0132\016.px.HeaderInfo\022\037\n\twaypoints\030\002 \003(\0132" - "\014.px.Waypoint\"\237\001\n\016PointCloudXYZI\022\036\n\006head" - "er\030\001 \002(\0132\016.px.HeaderInfo\022,\n\006points\030\002 \003(\013" - "2\034.px.PointCloudXYZI.PointXYZI\032\?\n\tPointX" - "YZI\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z\030\003 \002(\002\022\021\n\t" - "intensity\030\004 \002(\002\"\241\001\n\020PointCloudXYZRGB\022\036\n\006" - "header\030\001 \002(\0132\016.px.HeaderInfo\0220\n\006points\030\002" - " \003(\0132 .px.PointCloudXYZRGB.PointXYZRGB\032;" - "\n\013PointXYZRGB\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z" - "\030\003 \002(\002\022\013\n\003rgb\030\004 \002(\002\"\365\002\n\tRGBDImage\022\036\n\006hea" - "der\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004cols\030\002 \002(\r\022" - "\014\n\004rows\030\003 \002(\r\022\r\n\005step1\030\004 \002(\r\022\r\n\005type1\030\005 " - "\002(\r\022\022\n\nimageData1\030\006 \002(\014\022\r\n\005step2\030\007 \002(\r\022\r" - "\n\005type2\030\010 \002(\r\022\022\n\nimageData2\030\t \002(\014\022\025\n\rcam" - "era_config\030\n \001(\r\022\023\n\013camera_type\030\013 \001(\r\022\014\n" - "\004roll\030\014 \001(\002\022\r\n\005pitch\030\r \001(\002\022\013\n\003yaw\030\016 \001(\002\022" - "\013\n\003lon\030\017 \001(\002\022\013\n\003lat\030\020 \001(\002\022\013\n\003alt\030\021 \001(\002\022\020" - "\n\010ground_x\030\022 \001(\002\022\020\n\010ground_y\030\023 \001(\002\022\020\n\010gr" - "ound_z\030\024 \001(\002\022\025\n\rcamera_matrix\030\025 \003(\002\"U\n\010W" - "aypoint\022\t\n\001x\030\001 \002(\001\022\t\n\001y\030\002 \002(\001\022\t\n\001z\030\003 \001(\001" - "\022\014\n\004roll\030\004 \001(\001\022\r\n\005pitch\030\005 \001(\001\022\013\n\003yaw\030\006 \001" - "(\001", 1962); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( - "pixhawk.proto", &protobuf_RegisterTypes); - HeaderInfo::default_instance_ = new HeaderInfo(); - GLOverlay::default_instance_ = new GLOverlay(); - Obstacle::default_instance_ = new Obstacle(); - ObstacleList::default_instance_ = new ObstacleList(); - ObstacleMap::default_instance_ = new ObstacleMap(); - Path::default_instance_ = new Path(); - PointCloudXYZI::default_instance_ = new PointCloudXYZI(); - PointCloudXYZI_PointXYZI::default_instance_ = new PointCloudXYZI_PointXYZI(); - PointCloudXYZRGB::default_instance_ = new PointCloudXYZRGB(); - PointCloudXYZRGB_PointXYZRGB::default_instance_ = new PointCloudXYZRGB_PointXYZRGB(); - RGBDImage::default_instance_ = new RGBDImage(); - Waypoint::default_instance_ = new Waypoint(); - HeaderInfo::default_instance_->InitAsDefaultInstance(); - GLOverlay::default_instance_->InitAsDefaultInstance(); - Obstacle::default_instance_->InitAsDefaultInstance(); - ObstacleList::default_instance_->InitAsDefaultInstance(); - ObstacleMap::default_instance_->InitAsDefaultInstance(); - Path::default_instance_->InitAsDefaultInstance(); - PointCloudXYZI::default_instance_->InitAsDefaultInstance(); - PointCloudXYZI_PointXYZI::default_instance_->InitAsDefaultInstance(); - PointCloudXYZRGB::default_instance_->InitAsDefaultInstance(); - PointCloudXYZRGB_PointXYZRGB::default_instance_->InitAsDefaultInstance(); - RGBDImage::default_instance_->InitAsDefaultInstance(); - Waypoint::default_instance_->InitAsDefaultInstance(); - ::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_pixhawk_2eproto); -} - -// Force AddDescriptors() to be called at static initialization time. -struct StaticDescriptorInitializer_pixhawk_2eproto { - StaticDescriptorInitializer_pixhawk_2eproto() { - protobuf_AddDesc_pixhawk_2eproto(); - } -} static_descriptor_initializer_pixhawk_2eproto_; - - -// =================================================================== - -#ifndef _MSC_VER -const int HeaderInfo::kSourceSysidFieldNumber; -const int HeaderInfo::kSourceCompidFieldNumber; -const int HeaderInfo::kTimestampFieldNumber; -#endif // !_MSC_VER - -HeaderInfo::HeaderInfo() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void HeaderInfo::InitAsDefaultInstance() { -} - -HeaderInfo::HeaderInfo(const HeaderInfo& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void HeaderInfo::SharedCtor() { - _cached_size_ = 0; - source_sysid_ = 0; - source_compid_ = 0; - timestamp_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -HeaderInfo::~HeaderInfo() { - SharedDtor(); -} - -void HeaderInfo::SharedDtor() { - if (this != default_instance_) { - } -} - -void HeaderInfo::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* HeaderInfo::descriptor() { - protobuf_AssignDescriptorsOnce(); - return HeaderInfo_descriptor_; -} - -const HeaderInfo& HeaderInfo::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -HeaderInfo* HeaderInfo::default_instance_ = NULL; - -HeaderInfo* HeaderInfo::New() const { - return new HeaderInfo; -} - -void HeaderInfo::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - source_sysid_ = 0; - source_compid_ = 0; - timestamp_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool HeaderInfo::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required int32 source_sysid = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &source_sysid_))); - set_has_source_sysid(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(16)) goto parse_source_compid; - break; - } - - // required int32 source_compid = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_source_compid: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &source_compid_))); - set_has_source_compid(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(25)) goto parse_timestamp; - break; - } - - // required double timestamp = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_timestamp: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, ×tamp_))); - set_has_timestamp(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void HeaderInfo::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required int32 source_sysid = 1; - if (has_source_sysid()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->source_sysid(), output); - } - - // required int32 source_compid = 2; - if (has_source_compid()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->source_compid(), output); - } - - // required double timestamp = 3; - if (has_timestamp()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->timestamp(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* HeaderInfo::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required int32 source_sysid = 1; - if (has_source_sysid()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->source_sysid(), target); - } - - // required int32 source_compid = 2; - if (has_source_compid()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->source_compid(), target); - } - - // required double timestamp = 3; - if (has_timestamp()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->timestamp(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int HeaderInfo::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required int32 source_sysid = 1; - if (has_source_sysid()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->source_sysid()); - } - - // required int32 source_compid = 2; - if (has_source_compid()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->source_compid()); - } - - // required double timestamp = 3; - if (has_timestamp()) { - total_size += 1 + 8; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void HeaderInfo::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const HeaderInfo* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void HeaderInfo::MergeFrom(const HeaderInfo& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_source_sysid()) { - set_source_sysid(from.source_sysid()); - } - if (from.has_source_compid()) { - set_source_compid(from.source_compid()); - } - if (from.has_timestamp()) { - set_timestamp(from.timestamp()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void HeaderInfo::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void HeaderInfo::CopyFrom(const HeaderInfo& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool HeaderInfo::IsInitialized() const { - if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false; - - return true; -} - -void HeaderInfo::Swap(HeaderInfo* other) { - if (other != this) { - std::swap(source_sysid_, other->source_sysid_); - std::swap(source_compid_, other->source_compid_); - std::swap(timestamp_, other->timestamp_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata HeaderInfo::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = HeaderInfo_descriptor_; - metadata.reflection = HeaderInfo_reflection_; - return metadata; -} - - -// =================================================================== - -const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor() { - protobuf_AssignDescriptorsOnce(); - return GLOverlay_CoordinateFrameType_descriptor_; -} -bool GLOverlay_CoordinateFrameType_IsValid(int value) { - switch(value) { - case 0: - case 1: - return true; - default: - return false; - } -} - -#ifndef _MSC_VER -const GLOverlay_CoordinateFrameType GLOverlay::GLOBAL; -const GLOverlay_CoordinateFrameType GLOverlay::LOCAL; -const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MIN; -const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MAX; -const int GLOverlay::CoordinateFrameType_ARRAYSIZE; -#endif // _MSC_VER -const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor() { - protobuf_AssignDescriptorsOnce(); - return GLOverlay_Mode_descriptor_; -} -bool GLOverlay_Mode_IsValid(int value) { - switch(value) { - case 0: - case 1: - case 2: - case 3: - case 4: - case 5: - case 6: - case 7: - case 8: - case 9: - case 10: - case 11: - case 12: - case 13: - return true; - default: - return false; - } -} - -#ifndef _MSC_VER -const GLOverlay_Mode GLOverlay::POINTS; -const GLOverlay_Mode GLOverlay::LINES; -const GLOverlay_Mode GLOverlay::LINE_STRIP; -const GLOverlay_Mode GLOverlay::LINE_LOOP; -const GLOverlay_Mode GLOverlay::TRIANGLES; -const GLOverlay_Mode GLOverlay::TRIANGLE_STRIP; -const GLOverlay_Mode GLOverlay::TRIANGLE_FAN; -const GLOverlay_Mode GLOverlay::QUADS; -const GLOverlay_Mode GLOverlay::QUAD_STRIP; -const GLOverlay_Mode GLOverlay::POLYGON; -const GLOverlay_Mode GLOverlay::SOLID_CIRCLE; -const GLOverlay_Mode GLOverlay::WIRE_CIRCLE; -const GLOverlay_Mode GLOverlay::SOLID_CUBE; -const GLOverlay_Mode GLOverlay::WIRE_CUBE; -const GLOverlay_Mode GLOverlay::Mode_MIN; -const GLOverlay_Mode GLOverlay::Mode_MAX; -const int GLOverlay::Mode_ARRAYSIZE; -#endif // _MSC_VER -const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor() { - protobuf_AssignDescriptorsOnce(); - return GLOverlay_Identifier_descriptor_; -} -bool GLOverlay_Identifier_IsValid(int value) { - switch(value) { - case 14: - case 15: - case 16: - case 17: - case 18: - case 19: - case 20: - case 21: - case 22: - case 23: - case 24: - case 25: - return true; - default: - return false; - } -} - -#ifndef _MSC_VER -const GLOverlay_Identifier GLOverlay::END; -const GLOverlay_Identifier GLOverlay::VERTEX2F; -const GLOverlay_Identifier GLOverlay::VERTEX3F; -const GLOverlay_Identifier GLOverlay::ROTATEF; -const GLOverlay_Identifier GLOverlay::TRANSLATEF; -const GLOverlay_Identifier GLOverlay::SCALEF; -const GLOverlay_Identifier GLOverlay::PUSH_MATRIX; -const GLOverlay_Identifier GLOverlay::POP_MATRIX; -const GLOverlay_Identifier GLOverlay::COLOR3F; -const GLOverlay_Identifier GLOverlay::COLOR4F; -const GLOverlay_Identifier GLOverlay::POINTSIZE; -const GLOverlay_Identifier GLOverlay::LINEWIDTH; -const GLOverlay_Identifier GLOverlay::Identifier_MIN; -const GLOverlay_Identifier GLOverlay::Identifier_MAX; -const int GLOverlay::Identifier_ARRAYSIZE; -#endif // _MSC_VER -#ifndef _MSC_VER -const int GLOverlay::kHeaderFieldNumber; -const int GLOverlay::kNameFieldNumber; -const int GLOverlay::kCoordinateFrameTypeFieldNumber; -const int GLOverlay::kOriginXFieldNumber; -const int GLOverlay::kOriginYFieldNumber; -const int GLOverlay::kOriginZFieldNumber; -const int GLOverlay::kDataFieldNumber; -#endif // !_MSC_VER - -GLOverlay::GLOverlay() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void GLOverlay::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -GLOverlay::GLOverlay(const GLOverlay& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void GLOverlay::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - name_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - coordinateframetype_ = 0; - origin_x_ = 0; - origin_y_ = 0; - origin_z_ = 0; - data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -GLOverlay::~GLOverlay() { - SharedDtor(); -} - -void GLOverlay::SharedDtor() { - if (name_ != &::google::protobuf::internal::kEmptyString) { - delete name_; - } - if (data_ != &::google::protobuf::internal::kEmptyString) { - delete data_; - } - if (this != default_instance_) { - delete header_; - } -} - -void GLOverlay::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* GLOverlay::descriptor() { - protobuf_AssignDescriptorsOnce(); - return GLOverlay_descriptor_; -} - -const GLOverlay& GLOverlay::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -GLOverlay* GLOverlay::default_instance_ = NULL; - -GLOverlay* GLOverlay::New() const { - return new GLOverlay; -} - -void GLOverlay::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - if (has_name()) { - if (name_ != &::google::protobuf::internal::kEmptyString) { - name_->clear(); - } - } - coordinateframetype_ = 0; - origin_x_ = 0; - origin_y_ = 0; - origin_z_ = 0; - if (has_data()) { - if (data_ != &::google::protobuf::internal::kEmptyString) { - data_->clear(); - } - } - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool GLOverlay::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_name; - break; - } - - // optional string name = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_name: - DO_(::google::protobuf::internal::WireFormatLite::ReadString( - input, this->mutable_name())); - ::google::protobuf::internal::WireFormat::VerifyUTF8String( - this->name().data(), this->name().length(), - ::google::protobuf::internal::WireFormat::PARSE); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(24)) goto parse_coordinateFrameType; - break; - } - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_coordinateFrameType: - int value; - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( - input, &value))); - if (::px::GLOverlay_CoordinateFrameType_IsValid(value)) { - set_coordinateframetype(static_cast< ::px::GLOverlay_CoordinateFrameType >(value)); - } else { - mutable_unknown_fields()->AddVarint(3, value); - } - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(33)) goto parse_origin_x; - break; - } - - // optional double origin_x = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_origin_x: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &origin_x_))); - set_has_origin_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(41)) goto parse_origin_y; - break; - } - - // optional double origin_y = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_origin_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &origin_y_))); - set_has_origin_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(49)) goto parse_origin_z; - break; - } - - // optional double origin_z = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_origin_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &origin_z_))); - set_has_origin_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(58)) goto parse_data; - break; - } - - // optional bytes data = 7; - case 7: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_data: - DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( - input, this->mutable_data())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void GLOverlay::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // optional string name = 2; - if (has_name()) { - ::google::protobuf::internal::WireFormat::VerifyUTF8String( - this->name().data(), this->name().length(), - ::google::protobuf::internal::WireFormat::SERIALIZE); - ::google::protobuf::internal::WireFormatLite::WriteString( - 2, this->name(), output); - } - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - if (has_coordinateframetype()) { - ::google::protobuf::internal::WireFormatLite::WriteEnum( - 3, this->coordinateframetype(), output); - } - - // optional double origin_x = 4; - if (has_origin_x()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->origin_x(), output); - } - - // optional double origin_y = 5; - if (has_origin_y()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->origin_y(), output); - } - - // optional double origin_z = 6; - if (has_origin_z()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->origin_z(), output); - } - - // optional bytes data = 7; - if (has_data()) { - ::google::protobuf::internal::WireFormatLite::WriteBytes( - 7, this->data(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* GLOverlay::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // optional string name = 2; - if (has_name()) { - ::google::protobuf::internal::WireFormat::VerifyUTF8String( - this->name().data(), this->name().length(), - ::google::protobuf::internal::WireFormat::SERIALIZE); - target = - ::google::protobuf::internal::WireFormatLite::WriteStringToArray( - 2, this->name(), target); - } - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - if (has_coordinateframetype()) { - target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( - 3, this->coordinateframetype(), target); - } - - // optional double origin_x = 4; - if (has_origin_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->origin_x(), target); - } - - // optional double origin_y = 5; - if (has_origin_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->origin_y(), target); - } - - // optional double origin_z = 6; - if (has_origin_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->origin_z(), target); - } - - // optional bytes data = 7; - if (has_data()) { - target = - ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 7, this->data(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int GLOverlay::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - // optional string name = 2; - if (has_name()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::StringSize( - this->name()); - } - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - if (has_coordinateframetype()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::EnumSize(this->coordinateframetype()); - } - - // optional double origin_x = 4; - if (has_origin_x()) { - total_size += 1 + 8; - } - - // optional double origin_y = 5; - if (has_origin_y()) { - total_size += 1 + 8; - } - - // optional double origin_z = 6; - if (has_origin_z()) { - total_size += 1 + 8; - } - - // optional bytes data = 7; - if (has_data()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::BytesSize( - this->data()); - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void GLOverlay::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const GLOverlay* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void GLOverlay::MergeFrom(const GLOverlay& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - if (from.has_name()) { - set_name(from.name()); - } - if (from.has_coordinateframetype()) { - set_coordinateframetype(from.coordinateframetype()); - } - if (from.has_origin_x()) { - set_origin_x(from.origin_x()); - } - if (from.has_origin_y()) { - set_origin_y(from.origin_y()); - } - if (from.has_origin_z()) { - set_origin_z(from.origin_z()); - } - if (from.has_data()) { - set_data(from.data()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void GLOverlay::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void GLOverlay::CopyFrom(const GLOverlay& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool GLOverlay::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - return true; -} - -void GLOverlay::Swap(GLOverlay* other) { - if (other != this) { - std::swap(header_, other->header_); - std::swap(name_, other->name_); - std::swap(coordinateframetype_, other->coordinateframetype_); - std::swap(origin_x_, other->origin_x_); - std::swap(origin_y_, other->origin_y_); - std::swap(origin_z_, other->origin_z_); - std::swap(data_, other->data_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata GLOverlay::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = GLOverlay_descriptor_; - metadata.reflection = GLOverlay_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int Obstacle::kXFieldNumber; -const int Obstacle::kYFieldNumber; -const int Obstacle::kZFieldNumber; -const int Obstacle::kLengthFieldNumber; -const int Obstacle::kWidthFieldNumber; -const int Obstacle::kHeightFieldNumber; -#endif // !_MSC_VER - -Obstacle::Obstacle() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void Obstacle::InitAsDefaultInstance() { -} - -Obstacle::Obstacle(const Obstacle& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void Obstacle::SharedCtor() { - _cached_size_ = 0; - x_ = 0; - y_ = 0; - z_ = 0; - length_ = 0; - width_ = 0; - height_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -Obstacle::~Obstacle() { - SharedDtor(); -} - -void Obstacle::SharedDtor() { - if (this != default_instance_) { - } -} - -void Obstacle::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* Obstacle::descriptor() { - protobuf_AssignDescriptorsOnce(); - return Obstacle_descriptor_; -} - -const Obstacle& Obstacle::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -Obstacle* Obstacle::default_instance_ = NULL; - -Obstacle* Obstacle::New() const { - return new Obstacle; -} - -void Obstacle::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - x_ = 0; - y_ = 0; - z_ = 0; - length_ = 0; - width_ = 0; - height_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool Obstacle::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // optional float x = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &x_))); - set_has_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(21)) goto parse_y; - break; - } - - // optional float y = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &y_))); - set_has_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(29)) goto parse_z; - break; - } - - // optional float z = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &z_))); - set_has_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(37)) goto parse_length; - break; - } - - // optional float length = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_length: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &length_))); - set_has_length(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(45)) goto parse_width; - break; - } - - // optional float width = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_width: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &width_))); - set_has_width(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(53)) goto parse_height; - break; - } - - // optional float height = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_height: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &height_))); - set_has_height(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void Obstacle::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // optional float x = 1; - if (has_x()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output); - } - - // optional float y = 2; - if (has_y()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output); - } - - // optional float z = 3; - if (has_z()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output); - } - - // optional float length = 4; - if (has_length()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->length(), output); - } - - // optional float width = 5; - if (has_width()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(5, this->width(), output); - } - - // optional float height = 6; - if (has_height()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(6, this->height(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* Obstacle::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // optional float x = 1; - if (has_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target); - } - - // optional float y = 2; - if (has_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target); - } - - // optional float z = 3; - if (has_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target); - } - - // optional float length = 4; - if (has_length()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->length(), target); - } - - // optional float width = 5; - if (has_width()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(5, this->width(), target); - } - - // optional float height = 6; - if (has_height()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(6, this->height(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int Obstacle::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // optional float x = 1; - if (has_x()) { - total_size += 1 + 4; - } - - // optional float y = 2; - if (has_y()) { - total_size += 1 + 4; - } - - // optional float z = 3; - if (has_z()) { - total_size += 1 + 4; - } - - // optional float length = 4; - if (has_length()) { - total_size += 1 + 4; - } - - // optional float width = 5; - if (has_width()) { - total_size += 1 + 4; - } - - // optional float height = 6; - if (has_height()) { - total_size += 1 + 4; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void Obstacle::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const Obstacle* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void Obstacle::MergeFrom(const Obstacle& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_x()) { - set_x(from.x()); - } - if (from.has_y()) { - set_y(from.y()); - } - if (from.has_z()) { - set_z(from.z()); - } - if (from.has_length()) { - set_length(from.length()); - } - if (from.has_width()) { - set_width(from.width()); - } - if (from.has_height()) { - set_height(from.height()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void Obstacle::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void Obstacle::CopyFrom(const Obstacle& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool Obstacle::IsInitialized() const { - - return true; -} - -void Obstacle::Swap(Obstacle* other) { - if (other != this) { - std::swap(x_, other->x_); - std::swap(y_, other->y_); - std::swap(z_, other->z_); - std::swap(length_, other->length_); - std::swap(width_, other->width_); - std::swap(height_, other->height_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata Obstacle::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = Obstacle_descriptor_; - metadata.reflection = Obstacle_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int ObstacleList::kHeaderFieldNumber; -const int ObstacleList::kObstaclesFieldNumber; -#endif // !_MSC_VER - -ObstacleList::ObstacleList() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void ObstacleList::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -ObstacleList::ObstacleList(const ObstacleList& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void ObstacleList::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -ObstacleList::~ObstacleList() { - SharedDtor(); -} - -void ObstacleList::SharedDtor() { - if (this != default_instance_) { - delete header_; - } -} - -void ObstacleList::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* ObstacleList::descriptor() { - protobuf_AssignDescriptorsOnce(); - return ObstacleList_descriptor_; -} - -const ObstacleList& ObstacleList::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -ObstacleList* ObstacleList::default_instance_ = NULL; - -ObstacleList* ObstacleList::New() const { - return new ObstacleList; -} - -void ObstacleList::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - } - obstacles_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool ObstacleList::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_obstacles; - break; - } - - // repeated .px.Obstacle obstacles = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_obstacles: - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, add_obstacles())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_obstacles; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void ObstacleList::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // repeated .px.Obstacle obstacles = 2; - for (int i = 0; i < this->obstacles_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 2, this->obstacles(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* ObstacleList::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // repeated .px.Obstacle obstacles = 2; - for (int i = 0; i < this->obstacles_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 2, this->obstacles(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int ObstacleList::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - } - // repeated .px.Obstacle obstacles = 2; - total_size += 1 * this->obstacles_size(); - for (int i = 0; i < this->obstacles_size(); i++) { - total_size += - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->obstacles(i)); - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void ObstacleList::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const ObstacleList* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void ObstacleList::MergeFrom(const ObstacleList& from) { - GOOGLE_CHECK_NE(&from, this); - obstacles_.MergeFrom(from.obstacles_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void ObstacleList::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void ObstacleList::CopyFrom(const ObstacleList& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool ObstacleList::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - return true; -} - -void ObstacleList::Swap(ObstacleList* other) { - if (other != this) { - std::swap(header_, other->header_); - obstacles_.Swap(&other->obstacles_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata ObstacleList::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = ObstacleList_descriptor_; - metadata.reflection = ObstacleList_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int ObstacleMap::kHeaderFieldNumber; -const int ObstacleMap::kTypeFieldNumber; -const int ObstacleMap::kResolutionFieldNumber; -const int ObstacleMap::kRowsFieldNumber; -const int ObstacleMap::kColsFieldNumber; -const int ObstacleMap::kMapR0FieldNumber; -const int ObstacleMap::kMapC0FieldNumber; -const int ObstacleMap::kArrayR0FieldNumber; -const int ObstacleMap::kArrayC0FieldNumber; -const int ObstacleMap::kDataFieldNumber; -#endif // !_MSC_VER - -ObstacleMap::ObstacleMap() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void ObstacleMap::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -ObstacleMap::ObstacleMap(const ObstacleMap& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void ObstacleMap::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - type_ = 0; - resolution_ = 0; - rows_ = 0; - cols_ = 0; - mapr0_ = 0; - mapc0_ = 0; - arrayr0_ = 0; - arrayc0_ = 0; - data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -ObstacleMap::~ObstacleMap() { - SharedDtor(); -} - -void ObstacleMap::SharedDtor() { - if (data_ != &::google::protobuf::internal::kEmptyString) { - delete data_; - } - if (this != default_instance_) { - delete header_; - } -} - -void ObstacleMap::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* ObstacleMap::descriptor() { - protobuf_AssignDescriptorsOnce(); - return ObstacleMap_descriptor_; -} - -const ObstacleMap& ObstacleMap::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -ObstacleMap* ObstacleMap::default_instance_ = NULL; - -ObstacleMap* ObstacleMap::New() const { - return new ObstacleMap; -} - -void ObstacleMap::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - type_ = 0; - resolution_ = 0; - rows_ = 0; - cols_ = 0; - mapr0_ = 0; - mapc0_ = 0; - arrayr0_ = 0; - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { - arrayc0_ = 0; - if (has_data()) { - if (data_ != &::google::protobuf::internal::kEmptyString) { - data_->clear(); - } - } - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool ObstacleMap::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(16)) goto parse_type; - break; - } - - // required int32 type = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_type: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &type_))); - set_has_type(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(29)) goto parse_resolution; - break; - } - - // optional float resolution = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_resolution: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &resolution_))); - set_has_resolution(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(32)) goto parse_rows; - break; - } - - // optional int32 rows = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_rows: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &rows_))); - set_has_rows(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(40)) goto parse_cols; - break; - } - - // optional int32 cols = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_cols: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &cols_))); - set_has_cols(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(48)) goto parse_mapR0; - break; - } - - // optional int32 mapR0 = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_mapR0: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &mapr0_))); - set_has_mapr0(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(56)) goto parse_mapC0; - break; - } - - // optional int32 mapC0 = 7; - case 7: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_mapC0: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &mapc0_))); - set_has_mapc0(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(64)) goto parse_arrayR0; - break; - } - - // optional int32 arrayR0 = 8; - case 8: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_arrayR0: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &arrayr0_))); - set_has_arrayr0(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(72)) goto parse_arrayC0; - break; - } - - // optional int32 arrayC0 = 9; - case 9: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_arrayC0: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &arrayc0_))); - set_has_arrayc0(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(82)) goto parse_data; - break; - } - - // optional bytes data = 10; - case 10: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_data: - DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( - input, this->mutable_data())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void ObstacleMap::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // required int32 type = 2; - if (has_type()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->type(), output); - } - - // optional float resolution = 3; - if (has_resolution()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->resolution(), output); - } - - // optional int32 rows = 4; - if (has_rows()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->rows(), output); - } - - // optional int32 cols = 5; - if (has_cols()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->cols(), output); - } - - // optional int32 mapR0 = 6; - if (has_mapr0()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->mapr0(), output); - } - - // optional int32 mapC0 = 7; - if (has_mapc0()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(7, this->mapc0(), output); - } - - // optional int32 arrayR0 = 8; - if (has_arrayr0()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(8, this->arrayr0(), output); - } - - // optional int32 arrayC0 = 9; - if (has_arrayc0()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(9, this->arrayc0(), output); - } - - // optional bytes data = 10; - if (has_data()) { - ::google::protobuf::internal::WireFormatLite::WriteBytes( - 10, this->data(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* ObstacleMap::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // required int32 type = 2; - if (has_type()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->type(), target); - } - - // optional float resolution = 3; - if (has_resolution()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->resolution(), target); - } - - // optional int32 rows = 4; - if (has_rows()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->rows(), target); - } - - // optional int32 cols = 5; - if (has_cols()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->cols(), target); - } - - // optional int32 mapR0 = 6; - if (has_mapr0()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->mapr0(), target); - } - - // optional int32 mapC0 = 7; - if (has_mapc0()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(7, this->mapc0(), target); - } - - // optional int32 arrayR0 = 8; - if (has_arrayr0()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(8, this->arrayr0(), target); - } - - // optional int32 arrayC0 = 9; - if (has_arrayc0()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(9, this->arrayc0(), target); - } - - // optional bytes data = 10; - if (has_data()) { - target = - ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 10, this->data(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int ObstacleMap::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - // required int32 type = 2; - if (has_type()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->type()); - } - - // optional float resolution = 3; - if (has_resolution()) { - total_size += 1 + 4; - } - - // optional int32 rows = 4; - if (has_rows()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->rows()); - } - - // optional int32 cols = 5; - if (has_cols()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->cols()); - } - - // optional int32 mapR0 = 6; - if (has_mapr0()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->mapr0()); - } - - // optional int32 mapC0 = 7; - if (has_mapc0()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->mapc0()); - } - - // optional int32 arrayR0 = 8; - if (has_arrayr0()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->arrayr0()); - } - - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { - // optional int32 arrayC0 = 9; - if (has_arrayc0()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->arrayc0()); - } - - // optional bytes data = 10; - if (has_data()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::BytesSize( - this->data()); - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void ObstacleMap::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const ObstacleMap* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void ObstacleMap::MergeFrom(const ObstacleMap& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - if (from.has_type()) { - set_type(from.type()); - } - if (from.has_resolution()) { - set_resolution(from.resolution()); - } - if (from.has_rows()) { - set_rows(from.rows()); - } - if (from.has_cols()) { - set_cols(from.cols()); - } - if (from.has_mapr0()) { - set_mapr0(from.mapr0()); - } - if (from.has_mapc0()) { - set_mapc0(from.mapc0()); - } - if (from.has_arrayr0()) { - set_arrayr0(from.arrayr0()); - } - } - if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) { - if (from.has_arrayc0()) { - set_arrayc0(from.arrayc0()); - } - if (from.has_data()) { - set_data(from.data()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void ObstacleMap::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void ObstacleMap::CopyFrom(const ObstacleMap& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool ObstacleMap::IsInitialized() const { - if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - return true; -} - -void ObstacleMap::Swap(ObstacleMap* other) { - if (other != this) { - std::swap(header_, other->header_); - std::swap(type_, other->type_); - std::swap(resolution_, other->resolution_); - std::swap(rows_, other->rows_); - std::swap(cols_, other->cols_); - std::swap(mapr0_, other->mapr0_); - std::swap(mapc0_, other->mapc0_); - std::swap(arrayr0_, other->arrayr0_); - std::swap(arrayc0_, other->arrayc0_); - std::swap(data_, other->data_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata ObstacleMap::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = ObstacleMap_descriptor_; - metadata.reflection = ObstacleMap_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int Path::kHeaderFieldNumber; -const int Path::kWaypointsFieldNumber; -#endif // !_MSC_VER - -Path::Path() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void Path::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -Path::Path(const Path& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void Path::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -Path::~Path() { - SharedDtor(); -} - -void Path::SharedDtor() { - if (this != default_instance_) { - delete header_; - } -} - -void Path::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* Path::descriptor() { - protobuf_AssignDescriptorsOnce(); - return Path_descriptor_; -} - -const Path& Path::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -Path* Path::default_instance_ = NULL; - -Path* Path::New() const { - return new Path; -} - -void Path::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - } - waypoints_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool Path::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_waypoints; - break; - } - - // repeated .px.Waypoint waypoints = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_waypoints: - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, add_waypoints())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_waypoints; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void Path::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // repeated .px.Waypoint waypoints = 2; - for (int i = 0; i < this->waypoints_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 2, this->waypoints(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* Path::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // repeated .px.Waypoint waypoints = 2; - for (int i = 0; i < this->waypoints_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 2, this->waypoints(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int Path::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - } - // repeated .px.Waypoint waypoints = 2; - total_size += 1 * this->waypoints_size(); - for (int i = 0; i < this->waypoints_size(); i++) { - total_size += - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->waypoints(i)); - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void Path::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const Path* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void Path::MergeFrom(const Path& from) { - GOOGLE_CHECK_NE(&from, this); - waypoints_.MergeFrom(from.waypoints_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void Path::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void Path::CopyFrom(const Path& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool Path::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - for (int i = 0; i < waypoints_size(); i++) { - if (!this->waypoints(i).IsInitialized()) return false; - } - return true; -} - -void Path::Swap(Path* other) { - if (other != this) { - std::swap(header_, other->header_); - waypoints_.Swap(&other->waypoints_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata Path::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = Path_descriptor_; - metadata.reflection = Path_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int PointCloudXYZI_PointXYZI::kXFieldNumber; -const int PointCloudXYZI_PointXYZI::kYFieldNumber; -const int PointCloudXYZI_PointXYZI::kZFieldNumber; -const int PointCloudXYZI_PointXYZI::kIntensityFieldNumber; -#endif // !_MSC_VER - -PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void PointCloudXYZI_PointXYZI::InitAsDefaultInstance() { -} - -PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI(const PointCloudXYZI_PointXYZI& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void PointCloudXYZI_PointXYZI::SharedCtor() { - _cached_size_ = 0; - x_ = 0; - y_ = 0; - z_ = 0; - intensity_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -PointCloudXYZI_PointXYZI::~PointCloudXYZI_PointXYZI() { - SharedDtor(); -} - -void PointCloudXYZI_PointXYZI::SharedDtor() { - if (this != default_instance_) { - } -} - -void PointCloudXYZI_PointXYZI::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI::descriptor() { - protobuf_AssignDescriptorsOnce(); - return PointCloudXYZI_PointXYZI_descriptor_; -} - -const PointCloudXYZI_PointXYZI& PointCloudXYZI_PointXYZI::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::default_instance_ = NULL; - -PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::New() const { - return new PointCloudXYZI_PointXYZI; -} - -void PointCloudXYZI_PointXYZI::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - x_ = 0; - y_ = 0; - z_ = 0; - intensity_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool PointCloudXYZI_PointXYZI::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required float x = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &x_))); - set_has_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(21)) goto parse_y; - break; - } - - // required float y = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &y_))); - set_has_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(29)) goto parse_z; - break; - } - - // required float z = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &z_))); - set_has_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(37)) goto parse_intensity; - break; - } - - // required float intensity = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_intensity: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &intensity_))); - set_has_intensity(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void PointCloudXYZI_PointXYZI::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required float x = 1; - if (has_x()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output); - } - - // required float y = 2; - if (has_y()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output); - } - - // required float z = 3; - if (has_z()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output); - } - - // required float intensity = 4; - if (has_intensity()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->intensity(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* PointCloudXYZI_PointXYZI::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required float x = 1; - if (has_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target); - } - - // required float y = 2; - if (has_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target); - } - - // required float z = 3; - if (has_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target); - } - - // required float intensity = 4; - if (has_intensity()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->intensity(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int PointCloudXYZI_PointXYZI::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required float x = 1; - if (has_x()) { - total_size += 1 + 4; - } - - // required float y = 2; - if (has_y()) { - total_size += 1 + 4; - } - - // required float z = 3; - if (has_z()) { - total_size += 1 + 4; - } - - // required float intensity = 4; - if (has_intensity()) { - total_size += 1 + 4; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void PointCloudXYZI_PointXYZI::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const PointCloudXYZI_PointXYZI* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void PointCloudXYZI_PointXYZI::MergeFrom(const PointCloudXYZI_PointXYZI& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_x()) { - set_x(from.x()); - } - if (from.has_y()) { - set_y(from.y()); - } - if (from.has_z()) { - set_z(from.z()); - } - if (from.has_intensity()) { - set_intensity(from.intensity()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void PointCloudXYZI_PointXYZI::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void PointCloudXYZI_PointXYZI::CopyFrom(const PointCloudXYZI_PointXYZI& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool PointCloudXYZI_PointXYZI::IsInitialized() const { - if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false; - - return true; -} - -void PointCloudXYZI_PointXYZI::Swap(PointCloudXYZI_PointXYZI* other) { - if (other != this) { - std::swap(x_, other->x_); - std::swap(y_, other->y_); - std::swap(z_, other->z_); - std::swap(intensity_, other->intensity_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata PointCloudXYZI_PointXYZI::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = PointCloudXYZI_PointXYZI_descriptor_; - metadata.reflection = PointCloudXYZI_PointXYZI_reflection_; - return metadata; -} - - -// ------------------------------------------------------------------- - -#ifndef _MSC_VER -const int PointCloudXYZI::kHeaderFieldNumber; -const int PointCloudXYZI::kPointsFieldNumber; -#endif // !_MSC_VER - -PointCloudXYZI::PointCloudXYZI() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void PointCloudXYZI::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -PointCloudXYZI::PointCloudXYZI(const PointCloudXYZI& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void PointCloudXYZI::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -PointCloudXYZI::~PointCloudXYZI() { - SharedDtor(); -} - -void PointCloudXYZI::SharedDtor() { - if (this != default_instance_) { - delete header_; - } -} - -void PointCloudXYZI::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* PointCloudXYZI::descriptor() { - protobuf_AssignDescriptorsOnce(); - return PointCloudXYZI_descriptor_; -} - -const PointCloudXYZI& PointCloudXYZI::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -PointCloudXYZI* PointCloudXYZI::default_instance_ = NULL; - -PointCloudXYZI* PointCloudXYZI::New() const { - return new PointCloudXYZI; -} - -void PointCloudXYZI::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - } - points_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool PointCloudXYZI::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_points; - break; - } - - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_points: - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, add_points())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_points; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void PointCloudXYZI::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - for (int i = 0; i < this->points_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 2, this->points(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* PointCloudXYZI::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - for (int i = 0; i < this->points_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 2, this->points(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int PointCloudXYZI::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - } - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - total_size += 1 * this->points_size(); - for (int i = 0; i < this->points_size(); i++) { - total_size += - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->points(i)); - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void PointCloudXYZI::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const PointCloudXYZI* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void PointCloudXYZI::MergeFrom(const PointCloudXYZI& from) { - GOOGLE_CHECK_NE(&from, this); - points_.MergeFrom(from.points_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void PointCloudXYZI::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void PointCloudXYZI::CopyFrom(const PointCloudXYZI& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool PointCloudXYZI::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - for (int i = 0; i < points_size(); i++) { - if (!this->points(i).IsInitialized()) return false; - } - return true; -} - -void PointCloudXYZI::Swap(PointCloudXYZI* other) { - if (other != this) { - std::swap(header_, other->header_); - points_.Swap(&other->points_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata PointCloudXYZI::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = PointCloudXYZI_descriptor_; - metadata.reflection = PointCloudXYZI_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int PointCloudXYZRGB_PointXYZRGB::kXFieldNumber; -const int PointCloudXYZRGB_PointXYZRGB::kYFieldNumber; -const int PointCloudXYZRGB_PointXYZRGB::kZFieldNumber; -const int PointCloudXYZRGB_PointXYZRGB::kRgbFieldNumber; -#endif // !_MSC_VER - -PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void PointCloudXYZRGB_PointXYZRGB::InitAsDefaultInstance() { -} - -PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB(const PointCloudXYZRGB_PointXYZRGB& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void PointCloudXYZRGB_PointXYZRGB::SharedCtor() { - _cached_size_ = 0; - x_ = 0; - y_ = 0; - z_ = 0; - rgb_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -PointCloudXYZRGB_PointXYZRGB::~PointCloudXYZRGB_PointXYZRGB() { - SharedDtor(); -} - -void PointCloudXYZRGB_PointXYZRGB::SharedDtor() { - if (this != default_instance_) { - } -} - -void PointCloudXYZRGB_PointXYZRGB::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB::descriptor() { - protobuf_AssignDescriptorsOnce(); - return PointCloudXYZRGB_PointXYZRGB_descriptor_; -} - -const PointCloudXYZRGB_PointXYZRGB& PointCloudXYZRGB_PointXYZRGB::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::default_instance_ = NULL; - -PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::New() const { - return new PointCloudXYZRGB_PointXYZRGB; -} - -void PointCloudXYZRGB_PointXYZRGB::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - x_ = 0; - y_ = 0; - z_ = 0; - rgb_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool PointCloudXYZRGB_PointXYZRGB::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required float x = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &x_))); - set_has_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(21)) goto parse_y; - break; - } - - // required float y = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &y_))); - set_has_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(29)) goto parse_z; - break; - } - - // required float z = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &z_))); - set_has_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(37)) goto parse_rgb; - break; - } - - // required float rgb = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_rgb: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &rgb_))); - set_has_rgb(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required float x = 1; - if (has_x()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output); - } - - // required float y = 2; - if (has_y()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output); - } - - // required float z = 3; - if (has_z()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output); - } - - // required float rgb = 4; - if (has_rgb()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->rgb(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required float x = 1; - if (has_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target); - } - - // required float y = 2; - if (has_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target); - } - - // required float z = 3; - if (has_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target); - } - - // required float rgb = 4; - if (has_rgb()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->rgb(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int PointCloudXYZRGB_PointXYZRGB::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required float x = 1; - if (has_x()) { - total_size += 1 + 4; - } - - // required float y = 2; - if (has_y()) { - total_size += 1 + 4; - } - - // required float z = 3; - if (has_z()) { - total_size += 1 + 4; - } - - // required float rgb = 4; - if (has_rgb()) { - total_size += 1 + 4; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const PointCloudXYZRGB_PointXYZRGB* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const PointCloudXYZRGB_PointXYZRGB& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_x()) { - set_x(from.x()); - } - if (from.has_y()) { - set_y(from.y()); - } - if (from.has_z()) { - set_z(from.z()); - } - if (from.has_rgb()) { - set_rgb(from.rgb()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const PointCloudXYZRGB_PointXYZRGB& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool PointCloudXYZRGB_PointXYZRGB::IsInitialized() const { - if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false; - - return true; -} - -void PointCloudXYZRGB_PointXYZRGB::Swap(PointCloudXYZRGB_PointXYZRGB* other) { - if (other != this) { - std::swap(x_, other->x_); - std::swap(y_, other->y_); - std::swap(z_, other->z_); - std::swap(rgb_, other->rgb_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata PointCloudXYZRGB_PointXYZRGB::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = PointCloudXYZRGB_PointXYZRGB_descriptor_; - metadata.reflection = PointCloudXYZRGB_PointXYZRGB_reflection_; - return metadata; -} - - -// ------------------------------------------------------------------- - -#ifndef _MSC_VER -const int PointCloudXYZRGB::kHeaderFieldNumber; -const int PointCloudXYZRGB::kPointsFieldNumber; -#endif // !_MSC_VER - -PointCloudXYZRGB::PointCloudXYZRGB() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void PointCloudXYZRGB::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -PointCloudXYZRGB::PointCloudXYZRGB(const PointCloudXYZRGB& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void PointCloudXYZRGB::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -PointCloudXYZRGB::~PointCloudXYZRGB() { - SharedDtor(); -} - -void PointCloudXYZRGB::SharedDtor() { - if (this != default_instance_) { - delete header_; - } -} - -void PointCloudXYZRGB::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* PointCloudXYZRGB::descriptor() { - protobuf_AssignDescriptorsOnce(); - return PointCloudXYZRGB_descriptor_; -} - -const PointCloudXYZRGB& PointCloudXYZRGB::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -PointCloudXYZRGB* PointCloudXYZRGB::default_instance_ = NULL; - -PointCloudXYZRGB* PointCloudXYZRGB::New() const { - return new PointCloudXYZRGB; -} - -void PointCloudXYZRGB::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - } - points_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool PointCloudXYZRGB::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_points; - break; - } - - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_points: - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, add_points())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_points; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void PointCloudXYZRGB::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - for (int i = 0; i < this->points_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 2, this->points(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* PointCloudXYZRGB::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - for (int i = 0; i < this->points_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 2, this->points(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int PointCloudXYZRGB::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - } - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - total_size += 1 * this->points_size(); - for (int i = 0; i < this->points_size(); i++) { - total_size += - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->points(i)); - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void PointCloudXYZRGB::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const PointCloudXYZRGB* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void PointCloudXYZRGB::MergeFrom(const PointCloudXYZRGB& from) { - GOOGLE_CHECK_NE(&from, this); - points_.MergeFrom(from.points_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void PointCloudXYZRGB::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void PointCloudXYZRGB::CopyFrom(const PointCloudXYZRGB& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool PointCloudXYZRGB::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - for (int i = 0; i < points_size(); i++) { - if (!this->points(i).IsInitialized()) return false; - } - return true; -} - -void PointCloudXYZRGB::Swap(PointCloudXYZRGB* other) { - if (other != this) { - std::swap(header_, other->header_); - points_.Swap(&other->points_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata PointCloudXYZRGB::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = PointCloudXYZRGB_descriptor_; - metadata.reflection = PointCloudXYZRGB_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int RGBDImage::kHeaderFieldNumber; -const int RGBDImage::kColsFieldNumber; -const int RGBDImage::kRowsFieldNumber; -const int RGBDImage::kStep1FieldNumber; -const int RGBDImage::kType1FieldNumber; -const int RGBDImage::kImageData1FieldNumber; -const int RGBDImage::kStep2FieldNumber; -const int RGBDImage::kType2FieldNumber; -const int RGBDImage::kImageData2FieldNumber; -const int RGBDImage::kCameraConfigFieldNumber; -const int RGBDImage::kCameraTypeFieldNumber; -const int RGBDImage::kRollFieldNumber; -const int RGBDImage::kPitchFieldNumber; -const int RGBDImage::kYawFieldNumber; -const int RGBDImage::kLonFieldNumber; -const int RGBDImage::kLatFieldNumber; -const int RGBDImage::kAltFieldNumber; -const int RGBDImage::kGroundXFieldNumber; -const int RGBDImage::kGroundYFieldNumber; -const int RGBDImage::kGroundZFieldNumber; -const int RGBDImage::kCameraMatrixFieldNumber; -#endif // !_MSC_VER - -RGBDImage::RGBDImage() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void RGBDImage::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -RGBDImage::RGBDImage(const RGBDImage& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void RGBDImage::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - cols_ = 0u; - rows_ = 0u; - step1_ = 0u; - type1_ = 0u; - imagedata1_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - step2_ = 0u; - type2_ = 0u; - imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - camera_config_ = 0u; - camera_type_ = 0u; - roll_ = 0; - pitch_ = 0; - yaw_ = 0; - lon_ = 0; - lat_ = 0; - alt_ = 0; - ground_x_ = 0; - ground_y_ = 0; - ground_z_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -RGBDImage::~RGBDImage() { - SharedDtor(); -} - -void RGBDImage::SharedDtor() { - if (imagedata1_ != &::google::protobuf::internal::kEmptyString) { - delete imagedata1_; - } - if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { - delete imagedata2_; - } - if (this != default_instance_) { - delete header_; - } -} - -void RGBDImage::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* RGBDImage::descriptor() { - protobuf_AssignDescriptorsOnce(); - return RGBDImage_descriptor_; -} - -const RGBDImage& RGBDImage::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -RGBDImage* RGBDImage::default_instance_ = NULL; - -RGBDImage* RGBDImage::New() const { - return new RGBDImage; -} - -void RGBDImage::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - cols_ = 0u; - rows_ = 0u; - step1_ = 0u; - type1_ = 0u; - if (has_imagedata1()) { - if (imagedata1_ != &::google::protobuf::internal::kEmptyString) { - imagedata1_->clear(); - } - } - step2_ = 0u; - type2_ = 0u; - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { - if (has_imagedata2()) { - if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { - imagedata2_->clear(); - } - } - camera_config_ = 0u; - camera_type_ = 0u; - roll_ = 0; - pitch_ = 0; - yaw_ = 0; - lon_ = 0; - lat_ = 0; - } - if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) { - alt_ = 0; - ground_x_ = 0; - ground_y_ = 0; - ground_z_ = 0; - } - camera_matrix_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool RGBDImage::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(16)) goto parse_cols; - break; - } - - // required uint32 cols = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_cols: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &cols_))); - set_has_cols(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(24)) goto parse_rows; - break; - } - - // required uint32 rows = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_rows: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &rows_))); - set_has_rows(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(32)) goto parse_step1; - break; - } - - // required uint32 step1 = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_step1: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &step1_))); - set_has_step1(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(40)) goto parse_type1; - break; - } - - // required uint32 type1 = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_type1: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &type1_))); - set_has_type1(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(50)) goto parse_imageData1; - break; - } - - // required bytes imageData1 = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_imageData1: - DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( - input, this->mutable_imagedata1())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(56)) goto parse_step2; - break; - } - - // required uint32 step2 = 7; - case 7: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_step2: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &step2_))); - set_has_step2(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(64)) goto parse_type2; - break; - } - - // required uint32 type2 = 8; - case 8: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_type2: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &type2_))); - set_has_type2(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(74)) goto parse_imageData2; - break; - } - - // required bytes imageData2 = 9; - case 9: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_imageData2: - DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( - input, this->mutable_imagedata2())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(80)) goto parse_camera_config; - break; - } - - // optional uint32 camera_config = 10; - case 10: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_camera_config: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &camera_config_))); - set_has_camera_config(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(88)) goto parse_camera_type; - break; - } - - // optional uint32 camera_type = 11; - case 11: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_camera_type: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &camera_type_))); - set_has_camera_type(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(101)) goto parse_roll; - break; - } - - // optional float roll = 12; - case 12: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_roll: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &roll_))); - set_has_roll(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(109)) goto parse_pitch; - break; - } - - // optional float pitch = 13; - case 13: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_pitch: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &pitch_))); - set_has_pitch(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(117)) goto parse_yaw; - break; - } - - // optional float yaw = 14; - case 14: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_yaw: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &yaw_))); - set_has_yaw(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(125)) goto parse_lon; - break; - } - - // optional float lon = 15; - case 15: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_lon: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &lon_))); - set_has_lon(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(133)) goto parse_lat; - break; - } - - // optional float lat = 16; - case 16: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_lat: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &lat_))); - set_has_lat(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(141)) goto parse_alt; - break; - } - - // optional float alt = 17; - case 17: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_alt: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &alt_))); - set_has_alt(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(149)) goto parse_ground_x; - break; - } - - // optional float ground_x = 18; - case 18: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_ground_x: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &ground_x_))); - set_has_ground_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(157)) goto parse_ground_y; - break; - } - - // optional float ground_y = 19; - case 19: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_ground_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &ground_y_))); - set_has_ground_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(165)) goto parse_ground_z; - break; - } - - // optional float ground_z = 20; - case 20: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_ground_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &ground_z_))); - set_has_ground_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(173)) goto parse_camera_matrix; - break; - } - - // repeated float camera_matrix = 21; - case 21: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_camera_matrix: - DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - 2, 173, input, this->mutable_camera_matrix()))); - } else if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) - == ::google::protobuf::internal::WireFormatLite:: - WIRETYPE_LENGTH_DELIMITED) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitiveNoInline< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, this->mutable_camera_matrix()))); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(173)) goto parse_camera_matrix; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void RGBDImage::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // required uint32 cols = 2; - if (has_cols()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(2, this->cols(), output); - } - - // required uint32 rows = 3; - if (has_rows()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->rows(), output); - } - - // required uint32 step1 = 4; - if (has_step1()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->step1(), output); - } - - // required uint32 type1 = 5; - if (has_type1()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(5, this->type1(), output); - } - - // required bytes imageData1 = 6; - if (has_imagedata1()) { - ::google::protobuf::internal::WireFormatLite::WriteBytes( - 6, this->imagedata1(), output); - } - - // required uint32 step2 = 7; - if (has_step2()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(7, this->step2(), output); - } - - // required uint32 type2 = 8; - if (has_type2()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(8, this->type2(), output); - } - - // required bytes imageData2 = 9; - if (has_imagedata2()) { - ::google::protobuf::internal::WireFormatLite::WriteBytes( - 9, this->imagedata2(), output); - } - - // optional uint32 camera_config = 10; - if (has_camera_config()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(10, this->camera_config(), output); - } - - // optional uint32 camera_type = 11; - if (has_camera_type()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(11, this->camera_type(), output); - } - - // optional float roll = 12; - if (has_roll()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(12, this->roll(), output); - } - - // optional float pitch = 13; - if (has_pitch()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(13, this->pitch(), output); - } - - // optional float yaw = 14; - if (has_yaw()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(14, this->yaw(), output); - } - - // optional float lon = 15; - if (has_lon()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(15, this->lon(), output); - } - - // optional float lat = 16; - if (has_lat()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(16, this->lat(), output); - } - - // optional float alt = 17; - if (has_alt()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(17, this->alt(), output); - } - - // optional float ground_x = 18; - if (has_ground_x()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(18, this->ground_x(), output); - } - - // optional float ground_y = 19; - if (has_ground_y()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(19, this->ground_y(), output); - } - - // optional float ground_z = 20; - if (has_ground_z()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(20, this->ground_z(), output); - } - - // repeated float camera_matrix = 21; - for (int i = 0; i < this->camera_matrix_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteFloat( - 21, this->camera_matrix(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* RGBDImage::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // required uint32 cols = 2; - if (has_cols()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(2, this->cols(), target); - } - - // required uint32 rows = 3; - if (has_rows()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->rows(), target); - } - - // required uint32 step1 = 4; - if (has_step1()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->step1(), target); - } - - // required uint32 type1 = 5; - if (has_type1()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(5, this->type1(), target); - } - - // required bytes imageData1 = 6; - if (has_imagedata1()) { - target = - ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 6, this->imagedata1(), target); - } - - // required uint32 step2 = 7; - if (has_step2()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(7, this->step2(), target); - } - - // required uint32 type2 = 8; - if (has_type2()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(8, this->type2(), target); - } - - // required bytes imageData2 = 9; - if (has_imagedata2()) { - target = - ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 9, this->imagedata2(), target); - } - - // optional uint32 camera_config = 10; - if (has_camera_config()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(10, this->camera_config(), target); - } - - // optional uint32 camera_type = 11; - if (has_camera_type()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(11, this->camera_type(), target); - } - - // optional float roll = 12; - if (has_roll()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(12, this->roll(), target); - } - - // optional float pitch = 13; - if (has_pitch()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(13, this->pitch(), target); - } - - // optional float yaw = 14; - if (has_yaw()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(14, this->yaw(), target); - } - - // optional float lon = 15; - if (has_lon()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(15, this->lon(), target); - } - - // optional float lat = 16; - if (has_lat()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(16, this->lat(), target); - } - - // optional float alt = 17; - if (has_alt()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(17, this->alt(), target); - } - - // optional float ground_x = 18; - if (has_ground_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(18, this->ground_x(), target); - } - - // optional float ground_y = 19; - if (has_ground_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(19, this->ground_y(), target); - } - - // optional float ground_z = 20; - if (has_ground_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(20, this->ground_z(), target); - } - - // repeated float camera_matrix = 21; - for (int i = 0; i < this->camera_matrix_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteFloatToArray(21, this->camera_matrix(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int RGBDImage::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - // required uint32 cols = 2; - if (has_cols()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->cols()); - } - - // required uint32 rows = 3; - if (has_rows()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->rows()); - } - - // required uint32 step1 = 4; - if (has_step1()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->step1()); - } - - // required uint32 type1 = 5; - if (has_type1()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->type1()); - } - - // required bytes imageData1 = 6; - if (has_imagedata1()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::BytesSize( - this->imagedata1()); - } - - // required uint32 step2 = 7; - if (has_step2()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->step2()); - } - - // required uint32 type2 = 8; - if (has_type2()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->type2()); - } - - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { - // required bytes imageData2 = 9; - if (has_imagedata2()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::BytesSize( - this->imagedata2()); - } - - // optional uint32 camera_config = 10; - if (has_camera_config()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->camera_config()); - } - - // optional uint32 camera_type = 11; - if (has_camera_type()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->camera_type()); - } - - // optional float roll = 12; - if (has_roll()) { - total_size += 1 + 4; - } - - // optional float pitch = 13; - if (has_pitch()) { - total_size += 1 + 4; - } - - // optional float yaw = 14; - if (has_yaw()) { - total_size += 1 + 4; - } - - // optional float lon = 15; - if (has_lon()) { - total_size += 1 + 4; - } - - // optional float lat = 16; - if (has_lat()) { - total_size += 2 + 4; - } - - } - if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) { - // optional float alt = 17; - if (has_alt()) { - total_size += 2 + 4; - } - - // optional float ground_x = 18; - if (has_ground_x()) { - total_size += 2 + 4; - } - - // optional float ground_y = 19; - if (has_ground_y()) { - total_size += 2 + 4; - } - - // optional float ground_z = 20; - if (has_ground_z()) { - total_size += 2 + 4; - } - - } - // repeated float camera_matrix = 21; - { - int data_size = 0; - data_size = 4 * this->camera_matrix_size(); - total_size += 2 * this->camera_matrix_size() + data_size; - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void RGBDImage::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const RGBDImage* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void RGBDImage::MergeFrom(const RGBDImage& from) { - GOOGLE_CHECK_NE(&from, this); - camera_matrix_.MergeFrom(from.camera_matrix_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - if (from.has_cols()) { - set_cols(from.cols()); - } - if (from.has_rows()) { - set_rows(from.rows()); - } - if (from.has_step1()) { - set_step1(from.step1()); - } - if (from.has_type1()) { - set_type1(from.type1()); - } - if (from.has_imagedata1()) { - set_imagedata1(from.imagedata1()); - } - if (from.has_step2()) { - set_step2(from.step2()); - } - if (from.has_type2()) { - set_type2(from.type2()); - } - } - if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) { - if (from.has_imagedata2()) { - set_imagedata2(from.imagedata2()); - } - if (from.has_camera_config()) { - set_camera_config(from.camera_config()); - } - if (from.has_camera_type()) { - set_camera_type(from.camera_type()); - } - if (from.has_roll()) { - set_roll(from.roll()); - } - if (from.has_pitch()) { - set_pitch(from.pitch()); - } - if (from.has_yaw()) { - set_yaw(from.yaw()); - } - if (from.has_lon()) { - set_lon(from.lon()); - } - if (from.has_lat()) { - set_lat(from.lat()); - } - } - if (from._has_bits_[16 / 32] & (0xffu << (16 % 32))) { - if (from.has_alt()) { - set_alt(from.alt()); - } - if (from.has_ground_x()) { - set_ground_x(from.ground_x()); - } - if (from.has_ground_y()) { - set_ground_y(from.ground_y()); - } - if (from.has_ground_z()) { - set_ground_z(from.ground_z()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void RGBDImage::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void RGBDImage::CopyFrom(const RGBDImage& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool RGBDImage::IsInitialized() const { - if ((_has_bits_[0] & 0x000001ff) != 0x000001ff) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - return true; -} - -void RGBDImage::Swap(RGBDImage* other) { - if (other != this) { - std::swap(header_, other->header_); - std::swap(cols_, other->cols_); - std::swap(rows_, other->rows_); - std::swap(step1_, other->step1_); - std::swap(type1_, other->type1_); - std::swap(imagedata1_, other->imagedata1_); - std::swap(step2_, other->step2_); - std::swap(type2_, other->type2_); - std::swap(imagedata2_, other->imagedata2_); - std::swap(camera_config_, other->camera_config_); - std::swap(camera_type_, other->camera_type_); - std::swap(roll_, other->roll_); - std::swap(pitch_, other->pitch_); - std::swap(yaw_, other->yaw_); - std::swap(lon_, other->lon_); - std::swap(lat_, other->lat_); - std::swap(alt_, other->alt_); - std::swap(ground_x_, other->ground_x_); - std::swap(ground_y_, other->ground_y_); - std::swap(ground_z_, other->ground_z_); - camera_matrix_.Swap(&other->camera_matrix_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata RGBDImage::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = RGBDImage_descriptor_; - metadata.reflection = RGBDImage_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int Waypoint::kXFieldNumber; -const int Waypoint::kYFieldNumber; -const int Waypoint::kZFieldNumber; -const int Waypoint::kRollFieldNumber; -const int Waypoint::kPitchFieldNumber; -const int Waypoint::kYawFieldNumber; -#endif // !_MSC_VER - -Waypoint::Waypoint() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void Waypoint::InitAsDefaultInstance() { -} - -Waypoint::Waypoint(const Waypoint& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void Waypoint::SharedCtor() { - _cached_size_ = 0; - x_ = 0; - y_ = 0; - z_ = 0; - roll_ = 0; - pitch_ = 0; - yaw_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -Waypoint::~Waypoint() { - SharedDtor(); -} - -void Waypoint::SharedDtor() { - if (this != default_instance_) { - } -} - -void Waypoint::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* Waypoint::descriptor() { - protobuf_AssignDescriptorsOnce(); - return Waypoint_descriptor_; -} - -const Waypoint& Waypoint::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -Waypoint* Waypoint::default_instance_ = NULL; - -Waypoint* Waypoint::New() const { - return new Waypoint; -} - -void Waypoint::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - x_ = 0; - y_ = 0; - z_ = 0; - roll_ = 0; - pitch_ = 0; - yaw_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool Waypoint::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required double x = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &x_))); - set_has_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(17)) goto parse_y; - break; - } - - // required double y = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &y_))); - set_has_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(25)) goto parse_z; - break; - } - - // optional double z = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &z_))); - set_has_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(33)) goto parse_roll; - break; - } - - // optional double roll = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_roll: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &roll_))); - set_has_roll(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(41)) goto parse_pitch; - break; - } - - // optional double pitch = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_pitch: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &pitch_))); - set_has_pitch(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(49)) goto parse_yaw; - break; - } - - // optional double yaw = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_yaw: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &yaw_))); - set_has_yaw(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void Waypoint::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required double x = 1; - if (has_x()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); - } - - // required double y = 2; - if (has_y()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); - } - - // optional double z = 3; - if (has_z()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); - } - - // optional double roll = 4; - if (has_roll()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->roll(), output); - } - - // optional double pitch = 5; - if (has_pitch()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->pitch(), output); - } - - // optional double yaw = 6; - if (has_yaw()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->yaw(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* Waypoint::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required double x = 1; - if (has_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); - } - - // required double y = 2; - if (has_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); - } - - // optional double z = 3; - if (has_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); - } - - // optional double roll = 4; - if (has_roll()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->roll(), target); - } - - // optional double pitch = 5; - if (has_pitch()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->pitch(), target); - } - - // optional double yaw = 6; - if (has_yaw()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->yaw(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int Waypoint::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required double x = 1; - if (has_x()) { - total_size += 1 + 8; - } - - // required double y = 2; - if (has_y()) { - total_size += 1 + 8; - } - - // optional double z = 3; - if (has_z()) { - total_size += 1 + 8; - } - - // optional double roll = 4; - if (has_roll()) { - total_size += 1 + 8; - } - - // optional double pitch = 5; - if (has_pitch()) { - total_size += 1 + 8; - } - - // optional double yaw = 6; - if (has_yaw()) { - total_size += 1 + 8; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void Waypoint::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const Waypoint* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void Waypoint::MergeFrom(const Waypoint& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_x()) { - set_x(from.x()); - } - if (from.has_y()) { - set_y(from.y()); - } - if (from.has_z()) { - set_z(from.z()); - } - if (from.has_roll()) { - set_roll(from.roll()); - } - if (from.has_pitch()) { - set_pitch(from.pitch()); - } - if (from.has_yaw()) { - set_yaw(from.yaw()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void Waypoint::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void Waypoint::CopyFrom(const Waypoint& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool Waypoint::IsInitialized() const { - if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false; - - return true; -} - -void Waypoint::Swap(Waypoint* other) { - if (other != this) { - std::swap(x_, other->x_); - std::swap(y_, other->y_); - std::swap(z_, other->z_); - std::swap(roll_, other->roll_); - std::swap(pitch_, other->pitch_); - std::swap(yaw_, other->yaw_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata Waypoint::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = Waypoint_descriptor_; - metadata.reflection = Waypoint_reflection_; - return metadata; -} - - -// @@protoc_insertion_point(namespace_scope) - -} // namespace px - -// @@protoc_insertion_point(global_scope) diff --git a/mavlink/share/pyshared/pymavlink/.gitignore b/mavlink/share/pyshared/pymavlink/.gitignore deleted file mode 100644 index 3d395ecda..000000000 --- a/mavlink/share/pyshared/pymavlink/.gitignore +++ /dev/null @@ -1,13 +0,0 @@ -apidocs/ -*.zip -*.pyc -send.sh -generator/C/include/ardupilotmega -generator/C/include/common -generator/C/include/pixhawk -generator/C/include/minimal -generator/C/include/ualberta -generator/C/include/slugs -testmav0.9* -testmav1.0* -Debug/ diff --git a/mavlink/share/pyshared/pymavlink/APM_Mavtest/APM_Mavtest.pde b/mavlink/share/pyshared/pymavlink/APM_Mavtest/APM_Mavtest.pde deleted file mode 100644 index b903b5c16..000000000 --- a/mavlink/share/pyshared/pymavlink/APM_Mavtest/APM_Mavtest.pde +++ /dev/null @@ -1,55 +0,0 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- - -/* - send all possible mavlink messages - Andrew Tridgell July 2011 -*/ - -// AVR runtime -#include -#include -#include -#include - -// Libraries -#include -#include -#include -#include "mavtest.h" - -FastSerialPort0(Serial); // FTDI/console -FastSerialPort1(Serial1); // GPS port -FastSerialPort3(Serial3); // Telemetry port - -#define SERIAL0_BAUD 115200 -#define SERIAL3_BAUD 115200 - -void setup() { - Serial.begin(SERIAL0_BAUD, 128, 128); - Serial3.begin(SERIAL3_BAUD, 128, 128); - mavlink_comm_0_port = &Serial; - mavlink_comm_1_port = &Serial3; -} - - - -void loop() -{ - Serial.println("Starting MAVLink test generator\n"); - while (1) { - mavlink_msg_heartbeat_send( - MAVLINK_COMM_0, - mavlink_system.type, - MAV_AUTOPILOT_ARDUPILOTMEGA); - - mavlink_msg_heartbeat_send( - MAVLINK_COMM_1, - mavlink_system.type, - MAV_AUTOPILOT_ARDUPILOTMEGA); - - mavtest_generate_outputs(MAVLINK_COMM_0); - mavtest_generate_outputs(MAVLINK_COMM_1); - delay(500); - } -} - diff --git a/mavlink/share/pyshared/pymavlink/README.txt b/mavlink/share/pyshared/pymavlink/README.txt deleted file mode 100644 index 386013e11..000000000 --- a/mavlink/share/pyshared/pymavlink/README.txt +++ /dev/null @@ -1,4 +0,0 @@ -This is a python implementation of the MAVLink protocol. - -Please see http://www.qgroundcontrol.org/mavlink/pymavlink for -documentation diff --git a/mavlink/share/pyshared/pymavlink/examples/apmsetrate.py b/mavlink/share/pyshared/pymavlink/examples/apmsetrate.py deleted file mode 100644 index d7d82256c..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/apmsetrate.py +++ /dev/null @@ -1,67 +0,0 @@ -#!/usr/bin/env python - -''' -set stream rate on an APM -''' - -import sys, struct, time, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("apmsetrate.py [options]") - -parser.add_option("--baudrate", dest="baudrate", type='int', - help="master port baud rate", default=115200) -parser.add_option("--device", dest="device", default=None, help="serial device") -parser.add_option("--rate", dest="rate", default=4, type='int', help="requested stream rate") -parser.add_option("--source-system", dest='SOURCE_SYSTEM', type='int', - default=255, help='MAVLink source system for this GCS') -parser.add_option("--showmessages", dest="showmessages", action='store_true', - help="show incoming messages", default=False) -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' - import mavlink10 as mavlink -else: - import mavlink -import mavutil - -if opts.device is None: - print("You must specify a serial device") - sys.exit(1) - -def wait_heartbeat(m): - '''wait for a heartbeat so we know the target system IDs''' - print("Waiting for APM heartbeat") - m.wait_heartbeat() - print("Heartbeat from APM (system %u component %u)" % (m.target_system, m.target_system)) - -def show_messages(m): - '''show incoming mavlink messages''' - while True: - msg = m.recv_match(blocking=True) - if not msg: - return - if msg.get_type() == "BAD_DATA": - if mavutil.all_printable(msg.data): - sys.stdout.write(msg.data) - sys.stdout.flush() - else: - print(msg) - -# create a mavlink serial instance -master = mavutil.mavlink_connection(opts.device, baud=opts.baudrate) - -# wait for the heartbeat msg to find the system ID -wait_heartbeat(master) - -print("Sending all stream request for rate %u" % opts.rate) -for i in range(0, 3): - master.mav.request_data_stream_send(master.target_system, master.target_component, - mavlink.MAV_DATA_STREAM_ALL, opts.rate, 1) -if opts.showmessages: - show_messages(master) diff --git a/mavlink/share/pyshared/pymavlink/examples/bwtest.py b/mavlink/share/pyshared/pymavlink/examples/bwtest.py deleted file mode 100644 index de56d4f8c..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/bwtest.py +++ /dev/null @@ -1,58 +0,0 @@ -#!/usr/bin/env python - -''' -check bandwidth of link -''' - -import sys, struct, time, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -import mavutil - -from optparse import OptionParser -parser = OptionParser("bwtest.py [options]") - -parser.add_option("--baudrate", dest="baudrate", type='int', - help="master port baud rate", default=115200) -parser.add_option("--device", dest="device", default=None, help="serial device") -(opts, args) = parser.parse_args() - -if opts.device is None: - print("You must specify a serial device") - sys.exit(1) - -# create a mavlink serial instance -master = mavutil.mavlink_connection(opts.device, baud=opts.baudrate) - -t1 = time.time() - -counts = {} - -bytes_sent = 0 -bytes_recv = 0 - -while True: - master.mav.heartbeat_send(1, 1) - master.mav.sys_status_send(1, 2, 3, 4, 5, 6, 7) - master.mav.gps_raw_send(1, 2, 3, 4, 5, 6, 7, 8, 9) - master.mav.attitude_send(1, 2, 3, 4, 5, 6, 7) - master.mav.vfr_hud_send(1, 2, 3, 4, 5, 6) - while master.port.inWaiting() > 0: - m = master.recv_msg() - if m == None: break - if m.get_type() not in counts: - counts[m.get_type()] = 0 - counts[m.get_type()] += 1 - t2 = time.time() - if t2 - t1 > 1.0: - print("%u sent, %u received, %u errors bwin=%.1f kB/s bwout=%.1f kB/s" % ( - master.mav.total_packets_sent, - master.mav.total_packets_received, - master.mav.total_receive_errors, - 0.001*(master.mav.total_bytes_received-bytes_recv)/(t2-t1), - 0.001*(master.mav.total_bytes_sent-bytes_sent)/(t2-t1))) - bytes_sent = master.mav.total_bytes_sent - bytes_recv = master.mav.total_bytes_received - t1 = t2 diff --git a/mavlink/share/pyshared/pymavlink/examples/flightmodes.py b/mavlink/share/pyshared/pymavlink/examples/flightmodes.py deleted file mode 100644 index 03d7e2c47..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/flightmodes.py +++ /dev/null @@ -1,52 +0,0 @@ -#!/usr/bin/env python - -''' -show changes in flight modes -''' - -import sys, time, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("flightmodes.py [options]") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") - -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 1: - print("Usage: flightmodes.py [options] ") - sys.exit(1) - -def flight_modes(logfile): - '''show flight modes for a log file''' - print("Processing log %s" % filename) - mlog = mavutil.mavlink_connection(filename) - - mode = -1 - nav_mode = -1 - - filesize = os.path.getsize(filename) - - while True: - m = mlog.recv_match(type='SYS_STATUS', - condition='SYS_STATUS.mode != %u or SYS_STATUS.nav_mode != %u' % (mode, nav_mode)) - if m is None: - return - mode = m.mode - nav_mode = m.nav_mode - pct = (100.0 * mlog.f.tell()) / filesize - print('%s MAV.flightmode=%-12s mode=%u nav_mode=%u (MAV.timestamp=%u %u%%)' % ( - time.asctime(time.localtime(m._timestamp)), - mlog.flightmode, - mode, nav_mode, m._timestamp, pct)) - -for filename in args: - flight_modes(filename) - - diff --git a/mavlink/share/pyshared/pymavlink/examples/flighttime.py b/mavlink/share/pyshared/pymavlink/examples/flighttime.py deleted file mode 100644 index 81cd38c94..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/flighttime.py +++ /dev/null @@ -1,59 +0,0 @@ -#!/usr/bin/env python - -''' -work out total flight time for a mavlink log -''' - -import sys, time, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("flighttime.py [options]") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") - -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 1: - print("Usage: flighttime.py [options] ") - sys.exit(1) - -def flight_time(logfile): - '''work out flight time for a log file''' - print("Processing log %s" % filename) - mlog = mavutil.mavlink_connection(filename) - - in_air = False - start_time = 0.0 - total_time = 0.0 - t = None - - while True: - m = mlog.recv_match(type='VFR_HUD') - if m is None: - if in_air: - total_time += time.mktime(t) - start_time - if total_time > 0: - print("Flight time : %u:%02u" % (int(total_time)/60, int(total_time)%60)) - return total_time - t = time.localtime(m._timestamp) - if m.groundspeed > 3.0 and not in_air: - print("In air at %s" % time.asctime(t)) - in_air = True - start_time = time.mktime(t) - elif m.groundspeed < 3.0 and in_air: - print("On ground at %s" % time.asctime(t)) - in_air = False - total_time += time.mktime(t) - start_time - return total_time - -total = 0.0 -for filename in args: - total += flight_time(filename) - -print("Total time in air: %u:%02u" % (int(total)/60, int(total)%60)) diff --git a/mavlink/share/pyshared/pymavlink/examples/gpslock.py b/mavlink/share/pyshared/pymavlink/examples/gpslock.py deleted file mode 100644 index f15b29072..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/gpslock.py +++ /dev/null @@ -1,68 +0,0 @@ -#!/usr/bin/env python - -''' -show GPS lock events in a MAVLink log -''' - -import sys, time, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("gpslock.py [options]") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") - -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 1: - print("Usage: gpslock.py [options] ") - sys.exit(1) - -def lock_time(logfile): - '''work out gps lock times for a log file''' - print("Processing log %s" % filename) - mlog = mavutil.mavlink_connection(filename) - - locked = False - start_time = 0.0 - total_time = 0.0 - t = None - m = mlog.recv_match(type='GPS_RAW') - unlock_time = time.mktime(time.localtime(m._timestamp)) - - while True: - m = mlog.recv_match(type='GPS_RAW') - if m is None: - if locked: - total_time += time.mktime(t) - start_time - if total_time > 0: - print("Lock time : %u:%02u" % (int(total_time)/60, int(total_time)%60)) - return total_time - t = time.localtime(m._timestamp) - if m.fix_type == 2 and not locked: - print("Locked at %s after %u seconds" % (time.asctime(t), - time.mktime(t) - unlock_time)) - locked = True - start_time = time.mktime(t) - elif m.fix_type == 1 and locked: - print("Lost GPS lock at %s" % time.asctime(t)) - locked = False - total_time += time.mktime(t) - start_time - unlock_time = time.mktime(t) - elif m.fix_type == 0 and locked: - print("Lost protocol lock at %s" % time.asctime(t)) - locked = False - total_time += time.mktime(t) - start_time - unlock_time = time.mktime(t) - return total_time - -total = 0.0 -for filename in args: - total += lock_time(filename) - -print("Total time locked: %u:%02u" % (int(total)/60, int(total)%60)) diff --git a/mavlink/share/pyshared/pymavlink/examples/magfit.py b/mavlink/share/pyshared/pymavlink/examples/magfit.py deleted file mode 100644 index 7bfda796b..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/magfit.py +++ /dev/null @@ -1,138 +0,0 @@ -#!/usr/bin/env python - -''' -fit best estimate of magnetometer offsets -''' - -import sys, time, os, math - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("magfit.py [options]") -parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps") -parser.add_option("--condition",dest="condition", default=None, help="select packets by condition") -parser.add_option("--noise", type='float', default=0, help="noise to add") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") - -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil -from rotmat import Vector3 - -if len(args) < 1: - print("Usage: magfit.py [options] ") - sys.exit(1) - -def noise(): - '''a noise vector''' - from random import gauss - v = Vector3(gauss(0, 1), gauss(0, 1), gauss(0, 1)) - v.normalize() - return v * opts.noise - -def select_data(data): - ret = [] - counts = {} - for d in data: - mag = d - key = "%u:%u:%u" % (mag.x/20,mag.y/20,mag.z/20) - if key in counts: - counts[key] += 1 - else: - counts[key] = 1 - if counts[key] < 3: - ret.append(d) - print(len(data), len(ret)) - return ret - -def radius(mag, offsets): - '''return radius give data point and offsets''' - return (mag + offsets).length() - -def radius_cmp(a, b, offsets): - '''return radius give data point and offsets''' - diff = radius(a, offsets) - radius(b, offsets) - if diff > 0: - return 1 - if diff < 0: - return -1 - return 0 - -def sphere_error(p, data): - from scipy import sqrt - x,y,z,r = p - ofs = Vector3(x,y,z) - ret = [] - for d in data: - mag = d - err = r - radius(mag, ofs) - ret.append(err) - return ret - -def fit_data(data): - import numpy, scipy - from scipy import optimize - - p0 = [0.0, 0.0, 0.0, 0.0] - p1, ier = optimize.leastsq(sphere_error, p0[:], args=(data)) - if not ier in [1, 2, 3, 4]: - raise RuntimeError("Unable to find solution") - return (Vector3(p1[0], p1[1], p1[2]), p1[3]) - -def magfit(logfile): - '''find best magnetometer offset fit to a log file''' - - print("Processing log %s" % filename) - mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps) - - data = [] - - last_t = 0 - offsets = Vector3(0,0,0) - - # now gather all the data - while True: - m = mlog.recv_match(condition=opts.condition) - if m is None: - break - if m.get_type() == "SENSOR_OFFSETS": - # update current offsets - offsets = Vector3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z) - if m.get_type() == "RAW_IMU": - mag = Vector3(m.xmag, m.ymag, m.zmag) - # add data point after subtracting the current offsets - data.append(mag - offsets + noise()) - - print("Extracted %u data points" % len(data)) - print("Current offsets: %s" % offsets) - - data = select_data(data) - - # do an initial fit with all data - (offsets, field_strength) = fit_data(data) - - for count in range(3): - # sort the data by the radius - data.sort(lambda a,b : radius_cmp(a,b,offsets)) - - print("Fit %u : %s field_strength=%6.1f to %6.1f" % ( - count, offsets, - radius(data[0], offsets), radius(data[-1], offsets))) - - # discard outliers, keep the middle 3/4 - data = data[len(data)/8:-len(data)/8] - - # fit again - (offsets, field_strength) = fit_data(data) - - print("Final : %s field_strength=%6.1f to %6.1f" % ( - offsets, - radius(data[0], offsets), radius(data[-1], offsets))) - -total = 0.0 -for filename in args: - magfit(filename) diff --git a/mavlink/share/pyshared/pymavlink/examples/magfit_delta.py b/mavlink/share/pyshared/pymavlink/examples/magfit_delta.py deleted file mode 100644 index 87d2dbb7f..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/magfit_delta.py +++ /dev/null @@ -1,145 +0,0 @@ -#!/usr/bin/env python - -''' -fit best estimate of magnetometer offsets using the algorithm from -Bill Premerlani -''' - -import sys, time, os, math - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -# command line option handling -from optparse import OptionParser -parser = OptionParser("magfit_delta.py [options]") -parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps") -parser.add_option("--condition",dest="condition", default=None, help="select packets by condition") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") -parser.add_option("--verbose", action='store_true', default=False, help="verbose offset output") -parser.add_option("--gain", type='float', default=0.01, help="algorithm gain") -parser.add_option("--noise", type='float', default=0, help="noise to add") -parser.add_option("--max-change", type='float', default=10, help="max step change") -parser.add_option("--min-diff", type='float', default=50, help="min mag vector delta") -parser.add_option("--history", type='int', default=20, help="how many points to keep") -parser.add_option("--repeat", type='int', default=1, help="number of repeats through the data") - -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil -from rotmat import Vector3, Matrix3 - -if len(args) < 1: - print("Usage: magfit_delta.py [options] ") - sys.exit(1) - -def noise(): - '''a noise vector''' - from random import gauss - v = Vector3(gauss(0, 1), gauss(0, 1), gauss(0, 1)) - v.normalize() - return v * opts.noise - -def find_offsets(data, ofs): - '''find mag offsets by applying Bills "offsets revisited" algorithm - on the data - - This is an implementation of the algorithm from: - http://gentlenav.googlecode.com/files/MagnetometerOffsetNullingRevisited.pdf - ''' - - # a limit on the maximum change in each step - max_change = opts.max_change - - # the gain factor for the algorithm - gain = opts.gain - - data2 = [] - for d in data: - d = d.copy() + noise() - d.x = float(int(d.x + 0.5)) - d.y = float(int(d.y + 0.5)) - d.z = float(int(d.z + 0.5)) - data2.append(d) - data = data2 - - history_idx = 0 - mag_history = data[0:opts.history] - - for i in range(opts.history, len(data)): - B1 = mag_history[history_idx] + ofs - B2 = data[i] + ofs - - diff = B2 - B1 - diff_length = diff.length() - if diff_length <= opts.min_diff: - # the mag vector hasn't changed enough - we don't get any - # information from this - history_idx = (history_idx+1) % opts.history - continue - - mag_history[history_idx] = data[i] - history_idx = (history_idx+1) % opts.history - - # equation 6 of Bills paper - delta = diff * (gain * (B2.length() - B1.length()) / diff_length) - - # limit the change from any one reading. This is to prevent - # single crazy readings from throwing off the offsets for a long - # time - delta_length = delta.length() - if max_change != 0 and delta_length > max_change: - delta *= max_change / delta_length - - # set the new offsets - ofs = ofs - delta - - if opts.verbose: - print ofs - return ofs - - -def magfit(logfile): - '''find best magnetometer offset fit to a log file''' - - print("Processing log %s" % filename) - - # open the log file - mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps) - - data = [] - mag = None - offsets = Vector3(0,0,0) - - # now gather all the data - while True: - # get the next MAVLink message in the log - m = mlog.recv_match(condition=opts.condition) - if m is None: - break - if m.get_type() == "SENSOR_OFFSETS": - # update offsets that were used during this flight - offsets = Vector3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z) - if m.get_type() == "RAW_IMU" and offsets != None: - # extract one mag vector, removing the offsets that were - # used during that flight to get the raw sensor values - mag = Vector3(m.xmag, m.ymag, m.zmag) - offsets - data.append(mag) - - print("Extracted %u data points" % len(data)) - print("Current offsets: %s" % offsets) - - # run the fitting algorithm - ofs = offsets - ofs = Vector3(0,0,0) - for r in range(opts.repeat): - ofs = find_offsets(data, ofs) - print('Loop %u offsets %s' % (r, ofs)) - sys.stdout.flush() - print("New offsets: %s" % ofs) - -total = 0.0 -for filename in args: - magfit(filename) diff --git a/mavlink/share/pyshared/pymavlink/examples/magfit_gps.py b/mavlink/share/pyshared/pymavlink/examples/magfit_gps.py deleted file mode 100644 index 30ba45806..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/magfit_gps.py +++ /dev/null @@ -1,159 +0,0 @@ -#!/usr/bin/env python - -''' -fit best estimate of magnetometer offsets -''' - -import sys, time, os, math - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("magfit.py [options]") -parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") -parser.add_option("--minspeed", type='float', default=5.0, help="minimum ground speed to use") - -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 1: - print("Usage: magfit.py [options] ") - sys.exit(1) - -class vec3(object): - def __init__(self, x, y, z): - self.x = x - self.y = y - self.z = z - def __str__(self): - return "%.1f %.1f %.1f" % (self.x, self.y, self.z) - -def heading_error1(parm, data): - from math import sin, cos, atan2, degrees - from numpy import dot - xofs,yofs,zofs,a1,a2,a3,a4,a5,a6,a7,a8,a9,declination = parm - - ret = [] - for d in data: - x = d[0] + xofs - y = d[1] + yofs - z = d[2] + zofs - r = d[3] - p = d[4] - h = d[5] - - headX = x*cos(p) + y*sin(r)*sin(p) + z*cos(r)*sin(p) - headY = y*cos(r) - z*sin(r) - heading = degrees(atan2(-headY,headX)) + declination - if heading < 0: - heading += 360 - herror = h - heading - if herror > 180: - herror -= 360 - if herror < -180: - herror += 360 - ret.append(herror) - return ret - -def heading_error(parm, data): - from math import sin, cos, atan2, degrees - from numpy import dot - xofs,yofs,zofs,a1,a2,a3,a4,a5,a6,a7,a8,a9,declination = parm - - a = [[1.0,a2,a3],[a4,a5,a6],[a7,a8,a9]] - - ret = [] - for d in data: - x = d[0] + xofs - y = d[1] + yofs - z = d[2] + zofs - r = d[3] - p = d[4] - h = d[5] - mv = [x, y, z] - mv2 = dot(a, mv) - x = mv2[0] - y = mv2[1] - z = mv2[2] - - headX = x*cos(p) + y*sin(r)*sin(p) + z*cos(r)*sin(p) - headY = y*cos(r) - z*sin(r) - heading = degrees(atan2(-headY,headX)) + declination - if heading < 0: - heading += 360 - herror = h - heading - if herror > 180: - herror -= 360 - if herror < -180: - herror += 360 - ret.append(herror) - return ret - -def fit_data(data): - import numpy, scipy - from scipy import optimize - - p0 = [0.0, 0.0, 0.0, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0] - p1, ier = optimize.leastsq(heading_error1, p0[:], args=(data)) - -# p0 = p1[:] -# p1, ier = optimize.leastsq(heading_error, p0[:], args=(data)) - - print(p1) - if not ier in [1, 2, 3, 4]: - raise RuntimeError("Unable to find solution") - return p1 - -def magfit(logfile): - '''find best magnetometer offset fit to a log file''' - print("Processing log %s" % filename) - mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps) - - flying = False - gps_heading = 0.0 - - data = [] - - # get the current mag offsets - m = mlog.recv_match(type='SENSOR_OFFSETS') - offsets = vec3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z) - - attitude = mlog.recv_match(type='ATTITUDE') - - # now gather all the data - while True: - m = mlog.recv_match() - if m is None: - break - if m.get_type() == "GPS_RAW": - # flying if groundspeed more than 5 m/s - flying = (m.v > opts.minspeed and m.fix_type == 2) - gps_heading = m.hdg - if m.get_type() == "ATTITUDE": - attitude = m - if m.get_type() == "SENSOR_OFFSETS": - # update current offsets - offsets = vec3(m.mag_ofs_x, m.mag_ofs_y, m.mag_ofs_z) - if not flying: - continue - if m.get_type() == "RAW_IMU": - data.append((m.xmag - offsets.x, m.ymag - offsets.y, m.zmag - offsets.z, attitude.roll, attitude.pitch, gps_heading)) - print("Extracted %u data points" % len(data)) - print("Current offsets: %s" % offsets) - ofs2 = fit_data(data) - print("Declination estimate: %.1f" % ofs2[-1]) - new_offsets = vec3(ofs2[0], ofs2[1], ofs2[2]) - a = [[ofs2[3], ofs2[4], ofs2[5]], - [ofs2[6], ofs2[7], ofs2[8]], - [ofs2[9], ofs2[10], ofs2[11]]] - print(a) - print("New offsets : %s" % new_offsets) - -total = 0.0 -for filename in args: - magfit(filename) diff --git a/mavlink/share/pyshared/pymavlink/examples/magtest.py b/mavlink/share/pyshared/pymavlink/examples/magtest.py deleted file mode 100644 index 8b910f8fd..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/magtest.py +++ /dev/null @@ -1,120 +0,0 @@ -#!/usr/bin/env python - -''' -rotate APMs on bench to test magnetometers - -''' - -import sys, os, time -from math import radians - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -import mavlink, mavutil - -from optparse import OptionParser -parser = OptionParser("rotate.py [options]") - -parser.add_option("--device1", dest="device1", default=None, help="mavlink device1") -parser.add_option("--device2", dest="device2", default=None, help="mavlink device2") -parser.add_option("--baudrate", dest="baudrate", type='int', - help="master port baud rate", default=115200) -(opts, args) = parser.parse_args() - -if opts.device1 is None or opts.device2 is None: - print("You must specify a mavlink device") - sys.exit(1) - -def set_attitude(rc3, rc4): - global mav1, mav2 - values = [ 65535 ] * 8 - values[2] = rc3 - values[3] = rc4 - mav1.mav.rc_channels_override_send(mav1.target_system, mav1.target_component, *values) - mav2.mav.rc_channels_override_send(mav2.target_system, mav2.target_component, *values) - - -# create a mavlink instance -mav1 = mavutil.mavlink_connection(opts.device1, baud=opts.baudrate) - -# create a mavlink instance -mav2 = mavutil.mavlink_connection(opts.device2, baud=opts.baudrate) - -print("Waiting for HEARTBEAT") -mav1.wait_heartbeat() -mav2.wait_heartbeat() -print("Heartbeat from APM (system %u component %u)" % (mav1.target_system, mav1.target_system)) -print("Heartbeat from APM (system %u component %u)" % (mav2.target_system, mav2.target_system)) - -print("Waiting for MANUAL mode") -mav1.recv_match(type='SYS_STATUS', condition='SYS_STATUS.mode==2 and SYS_STATUS.nav_mode==4', blocking=True) -mav2.recv_match(type='SYS_STATUS', condition='SYS_STATUS.mode==2 and SYS_STATUS.nav_mode==4', blocking=True) - -print("Setting declination") -mav1.mav.param_set_send(mav1.target_system, mav1.target_component, - 'COMPASS_DEC', radians(12.33)) -mav2.mav.param_set_send(mav2.target_system, mav2.target_component, - 'COMPASS_DEC', radians(12.33)) - - -set_attitude(1060, 1160) - -event = mavutil.periodic_event(30) -pevent = mavutil.periodic_event(0.3) -rc3_min = 1060 -rc3_max = 1850 -rc4_min = 1080 -rc4_max = 1500 -rc3 = rc3_min -rc4 = 1160 -delta3 = 2 -delta4 = 1 -use_pitch = 1 - -MAV_ACTION_CALIBRATE_GYRO = 17 -mav1.mav.action_send(mav1.target_system, mav1.target_component, MAV_ACTION_CALIBRATE_GYRO) -mav2.mav.action_send(mav2.target_system, mav2.target_component, MAV_ACTION_CALIBRATE_GYRO) - -print("Waiting for gyro calibration") -mav1.recv_match(type='ACTION_ACK') -mav2.recv_match(type='ACTION_ACK') - -print("Resetting mag offsets") -mav1.mav.set_mag_offsets_send(mav1.target_system, mav1.target_component, 0, 0, 0) -mav2.mav.set_mag_offsets_send(mav2.target_system, mav2.target_component, 0, 0, 0) - -def TrueHeading(SERVO_OUTPUT_RAW): - p = float(SERVO_OUTPUT_RAW.servo3_raw - rc3_min) / (rc3_max - rc3_min) - return 172 + p*(326 - 172) - -while True: - mav1.recv_msg() - mav2.recv_msg() - if event.trigger(): - if not use_pitch: - rc4 = 1160 - set_attitude(rc3, rc4) - rc3 += delta3 - if rc3 > rc3_max or rc3 < rc3_min: - delta3 = -delta3 - use_pitch ^= 1 - rc4 += delta4 - if rc4 > rc4_max or rc4 < rc4_min: - delta4 = -delta4 - if pevent.trigger(): - print "hdg1: %3u hdg2: %3u ofs1: %4u, %4u, %4u ofs2: %4u, %4u, %4u" % ( - mav1.messages['VFR_HUD'].heading, - mav2.messages['VFR_HUD'].heading, - mav1.messages['SENSOR_OFFSETS'].mag_ofs_x, - mav1.messages['SENSOR_OFFSETS'].mag_ofs_y, - mav1.messages['SENSOR_OFFSETS'].mag_ofs_z, - mav2.messages['SENSOR_OFFSETS'].mag_ofs_x, - mav2.messages['SENSOR_OFFSETS'].mag_ofs_y, - mav2.messages['SENSOR_OFFSETS'].mag_ofs_z, - ) - time.sleep(0.01) - -# 314M 326G -# 160M 172G - diff --git a/mavlink/share/pyshared/pymavlink/examples/mavgraph.py b/mavlink/share/pyshared/pymavlink/examples/mavgraph.py deleted file mode 100644 index e19856487..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/mavgraph.py +++ /dev/null @@ -1,196 +0,0 @@ -#!/usr/bin/env python -''' -graph a MAVLink log file -Andrew Tridgell August 2011 -''' - -import sys, struct, time, os, datetime -import math, re -import pylab, pytz, matplotlib -from math import * - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from mavextra import * - -locator = None -formatter = None - -def plotit(x, y, fields, colors=[]): - '''plot a set of graphs using date for x axis''' - global locator, formatter - pylab.ion() - fig = pylab.figure(num=1, figsize=(12,6)) - ax1 = fig.gca() - ax2 = None - xrange = 0.0 - for i in range(0, len(fields)): - if len(x[i]) == 0: continue - if x[i][-1] - x[i][0] > xrange: - xrange = x[i][-1] - x[i][0] - xrange *= 24 * 60 * 60 - if formatter is None: - if xrange < 1000: - formatter = matplotlib.dates.DateFormatter('%H:%M:%S') - else: - formatter = matplotlib.dates.DateFormatter('%H:%M') - interval = 1 - intervals = [ 1, 2, 5, 10, 15, 30, 60, 120, 240, 300, 600, - 900, 1800, 3600, 7200, 5*3600, 10*3600, 24*3600 ] - for interval in intervals: - if xrange / interval < 15: - break - locator = matplotlib.dates.SecondLocator(interval=interval) - ax1.xaxis.set_major_locator(locator) - ax1.xaxis.set_major_formatter(formatter) - empty = True - ax1_labels = [] - ax2_labels = [] - for i in range(0, len(fields)): - if len(x[i]) == 0: - print("Failed to find any values for field %s" % fields[i]) - continue - if i < len(colors): - color = colors[i] - else: - color = 'red' - (tz, tzdst) = time.tzname - if axes[i] == 2: - if ax2 == None: - ax2 = ax1.twinx() - ax = ax2 - ax2.xaxis.set_major_locator(locator) - ax2.xaxis.set_major_formatter(formatter) - label = fields[i] - if label.endswith(":2"): - label = label[:-2] - ax2_labels.append(label) - else: - ax1_labels.append(fields[i]) - ax = ax1 - ax.plot_date(x[i], y[i], color=color, label=fields[i], - linestyle='-', marker='None', tz=None) - pylab.draw() - empty = False - if ax1_labels != []: - ax1.legend(ax1_labels,loc=opts.legend) - if ax2_labels != []: - ax2.legend(ax2_labels,loc=opts.legend2) - if empty: - print("No data to graph") - return - - -from optparse import OptionParser -parser = OptionParser("mavgraph.py [options] ") - -parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps") -parser.add_option("--planner",dest="planner", action='store_true', help="use planner file format") -parser.add_option("--condition",dest="condition", default=None, help="select packets by a condition") -parser.add_option("--labels",dest="labels", default=None, help="comma separated field labels") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") -parser.add_option("--legend", default='upper left', help="default legend position") -parser.add_option("--legend2", default='upper right', help="default legend2 position") -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 2: - print("Usage: mavlogdump.py [options] ") - sys.exit(1) - -filenames = [] -fields = [] -for f in args: - if os.path.exists(f): - filenames.append(f) - else: - fields.append(f) -msg_types = set() -multiplier = [] -field_types = [] - -colors = [ 'red', 'green', 'blue', 'orange', 'olive', 'black', 'grey' ] - -# work out msg types we are interested in -x = [] -y = [] -axes = [] -first_only = [] -re_caps = re.compile('[A-Z_]+') -for f in fields: - caps = set(re.findall(re_caps, f)) - msg_types = msg_types.union(caps) - field_types.append(caps) - y.append([]) - x.append([]) - axes.append(1) - first_only.append(False) - -def add_data(t, msg, vars): - '''add some data''' - mtype = msg.get_type() - if mtype not in msg_types: - return - for i in range(0, len(fields)): - if mtype not in field_types[i]: - continue - f = fields[i] - if f.endswith(":2"): - axes[i] = 2 - f = f[:-2] - if f.endswith(":1"): - first_only[i] = True - f = f[:-2] - v = mavutil.evaluate_expression(f, vars) - if v is None: - continue - y[i].append(v) - x[i].append(t) - -def process_file(filename): - '''process one file''' - print("Processing %s" % filename) - mlog = mavutil.mavlink_connection(filename, notimestamps=opts.notimestamps) - vars = {} - - while True: - msg = mlog.recv_match(opts.condition) - if msg is None: break - tdays = (msg._timestamp - time.timezone) / (24 * 60 * 60) - tdays += 719163 # pylab wants it since 0001-01-01 - add_data(tdays, msg, mlog.messages) - -if len(filenames) == 0: - print("No files to process") - sys.exit(1) - -if opts.labels is not None: - labels = opts.labels.split(',') - if len(labels) != len(fields)*len(filenames): - print("Number of labels (%u) must match number of fields (%u)" % ( - len(labels), len(fields)*len(filenames))) - sys.exit(1) -else: - labels = None - -for fi in range(0, len(filenames)): - f = filenames[fi] - process_file(f) - for i in range(0, len(x)): - if first_only[i] and fi != 0: - x[i] = [] - y[i] = [] - if labels: - lab = labels[fi*len(fields):(fi+1)*len(fields)] - else: - lab = fields[:] - plotit(x, y, lab, colors=colors[fi*len(fields):]) - for i in range(0, len(x)): - x[i] = [] - y[i] = [] -pylab.show() -raw_input('press enter to exit....') diff --git a/mavlink/share/pyshared/pymavlink/examples/mavlogdump.py b/mavlink/share/pyshared/pymavlink/examples/mavlogdump.py deleted file mode 100644 index f4cdc56bf..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/mavlogdump.py +++ /dev/null @@ -1,67 +0,0 @@ -#!/usr/bin/env python - -''' -example program that dumps a Mavlink log file. The log file is -assumed to be in the format that qgroundcontrol uses, which consists -of a series of MAVLink packets, each with a 64 bit timestamp -header. The timestamp is in microseconds since 1970 (unix epoch) -''' - -import sys, time, os, struct - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("mavlogdump.py [options]") - -parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps") -parser.add_option("--planner",dest="planner", action='store_true', help="use planner file format") -parser.add_option("--robust",dest="robust", action='store_true', help="Enable robust parsing (skip over bad data)") -parser.add_option("-f", "--follow",dest="follow", action='store_true', help="keep waiting for more data at end of file") -parser.add_option("--condition",dest="condition", default=None, help="select packets by condition") -parser.add_option("-q", "--quiet", dest="quiet", action='store_true', help="don't display packets") -parser.add_option("-o", "--output", default=None, help="output matching packets to give file") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") -parser.add_option("--types", default=None, help="types of messages (comma separated)") -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 1: - print("Usage: mavlogdump.py [options] ") - sys.exit(1) - -filename = args[0] -mlog = mavutil.mavlink_connection(filename, planner_format=opts.planner, - notimestamps=opts.notimestamps, - robust_parsing=opts.robust) - -output = None -if opts.output: - output = mavutil.mavlogfile(opts.output, write=True) - -types = opts.types -if types is not None: - types = types.split(',') - -while True: - m = mlog.recv_match(condition=opts.condition, blocking=opts.follow) - if m is None: - break - if types is not None and m.get_type() not in types: - continue - if output: - timestamp = getattr(m, '_timestamp', None) - if timestamp: - output.write(struct.pack('>Q', timestamp*1.0e6)) - output.write(m.get_msgbuf().tostring()) - if opts.quiet: - continue - print("%s.%02u: %s" % ( - time.strftime("%Y-%m-%d %H:%M:%S", - time.localtime(m._timestamp)), - int(m._timestamp*100.0)%100, m)) - diff --git a/mavlink/share/pyshared/pymavlink/examples/mavparms.py b/mavlink/share/pyshared/pymavlink/examples/mavparms.py deleted file mode 100644 index 702fbd9e1..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/mavparms.py +++ /dev/null @@ -1,48 +0,0 @@ -#!/usr/bin/env python - -''' -extract mavlink parameter values -''' - -import sys, time, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("mavparms.py [options]") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") - -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 1: - print("Usage: mavparms.py [options] ") - sys.exit(1) - -parms = {} - -def mavparms(logfile): - '''extract mavlink parameters''' - mlog = mavutil.mavlink_connection(filename) - - while True: - m = mlog.recv_match(type='PARAM_VALUE') - if m is None: - return - pname = str(m.param_id).strip() - if len(pname) > 0: - parms[pname] = m.param_value - -total = 0.0 -for filename in args: - mavparms(filename) - -keys = parms.keys() -keys.sort() -for p in keys: - print("%-15s %.6f" % (p, parms[p])) - diff --git a/mavlink/share/pyshared/pymavlink/examples/mavtest.py b/mavlink/share/pyshared/pymavlink/examples/mavtest.py deleted file mode 100644 index 3c385e48a..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/mavtest.py +++ /dev/null @@ -1,41 +0,0 @@ -#!/usr/bin/env python - -import sys, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -import mavlink - -class fifo(object): - def __init__(self): - self.buf = [] - def write(self, data): - self.buf += data - return len(data) - def read(self): - return self.buf.pop(0) - -f = fifo() - -# create a mavlink instance, which will do IO on file object 'f' -mav = mavlink.MAVLink(f) - -# set the WP_RADIUS parameter on the MAV at the end of the link -mav.param_set_send(7, 1, "WP_RADIUS", 101) - -# alternatively, produce a MAVLink_param_set object -# this can be sent via your own transport if you like -m = mav.param_set_encode(7, 1, "WP_RADIUS", 101) - -# get the encoded message as a buffer -b = m.get_msgbuf() - -# decode an incoming message -m2 = mav.decode(b) - -# show what fields it has -print("Got a message with id %u and fields %s" % (m2.get_msgId(), m2.get_fieldnames())) - -# print out the fields -print(m2) diff --git a/mavlink/share/pyshared/pymavlink/examples/mavtester.py b/mavlink/share/pyshared/pymavlink/examples/mavtester.py deleted file mode 100644 index 8b5284f3f..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/mavtester.py +++ /dev/null @@ -1,43 +0,0 @@ -#!/usr/bin/env python - -''' -test mavlink messages -''' - -import sys, struct, time, os -from curses import ascii - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -import mavlink, mavtest, mavutil - -from optparse import OptionParser -parser = OptionParser("mavtester.py [options]") - -parser.add_option("--baudrate", dest="baudrate", type='int', - help="master port baud rate", default=115200) -parser.add_option("--device", dest="device", default=None, help="serial device") -parser.add_option("--source-system", dest='SOURCE_SYSTEM', type='int', - default=255, help='MAVLink source system for this GCS') -(opts, args) = parser.parse_args() - -if opts.device is None: - print("You must specify a serial device") - sys.exit(1) - -def wait_heartbeat(m): - '''wait for a heartbeat so we know the target system IDs''' - print("Waiting for APM heartbeat") - msg = m.recv_match(type='HEARTBEAT', blocking=True) - print("Heartbeat from APM (system %u component %u)" % (m.target_system, m.target_system)) - -# create a mavlink serial instance -master = mavutil.mavlink_connection(opts.device, baud=opts.baudrate, source_system=opts.SOURCE_SYSTEM) - -# wait for the heartbeat msg to find the system ID -wait_heartbeat(master) - -print("Sending all message types") -mavtest.generate_outputs(master.mav) - diff --git a/mavlink/share/pyshared/pymavlink/examples/mavtogpx.py b/mavlink/share/pyshared/pymavlink/examples/mavtogpx.py deleted file mode 100644 index 92d3cb51c..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/mavtogpx.py +++ /dev/null @@ -1,83 +0,0 @@ -#!/usr/bin/env python - -''' -example program to extract GPS data from a mavlink log, and create a GPX -file, for loading into google earth -''' - -import sys, struct, time, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("mavtogpx.py [options]") -parser.add_option("--condition",dest="condition", default=None, help="select packets by a condition") -parser.add_option("--nofixcheck", default=False, action='store_true', help="don't check for GPS fix") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 1: - print("Usage: mavtogpx.py ") - sys.exit(1) - -def mav_to_gpx(infilename, outfilename): - '''convert a mavlink log file to a GPX file''' - - mlog = mavutil.mavlink_connection(infilename) - outf = open(outfilename, mode='w') - - def process_packet(m): - t = time.localtime(m._timestamp) - outf.write(''' - %s - - %s - %s - 3d - -''' % (m.lat, m.lon, m.alt, - time.strftime("%Y-%m-%dT%H:%M:%SZ", t), - m.hdg, m.v)) - - def add_header(): - outf.write(''' - - - -''') - - def add_footer(): - outf.write(''' - - -''') - - add_header() - - count=0 - while True: - m = mlog.recv_match(type='GPS_RAW', condition=opts.condition) - if m is None: break - if m.fix_type != 2 and not opts.nofixcheck: - continue - if m.lat == 0.0 or m.lon == 0.0: - continue - process_packet(m) - count += 1 - add_footer() - print("Created %s with %u points" % (outfilename, count)) - - -for infilename in args: - outfilename = infilename + '.gpx' - mav_to_gpx(infilename, outfilename) diff --git a/mavlink/share/pyshared/pymavlink/examples/rotmat.py b/mavlink/share/pyshared/pymavlink/examples/rotmat.py deleted file mode 100644 index 6d5405949..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/rotmat.py +++ /dev/null @@ -1,269 +0,0 @@ -#!/usr/bin/env python -# -# vector3 and rotation matrix classes -# This follows the conventions in the ArduPilot code, -# and is essentially a python version of the AP_Math library -# -# Andrew Tridgell, March 2012 -# -# This library is free software; you can redistribute it and/or modify it -# under the terms of the GNU Lesser General Public License as published by the -# Free Software Foundation; either version 2.1 of the License, or (at your -# option) any later version. -# -# This library is distributed in the hope that it will be useful, but WITHOUT -# ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or -# FITNESS FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License -# for more details. -# -# You should have received a copy of the GNU Lesser General Public License -# along with this library; if not, write to the Free Software Foundation, -# Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA - -'''rotation matrix class -''' - -from math import sin, cos, sqrt, asin, atan2, pi, radians, acos - -class Vector3: - '''a vector''' - def __init__(self, x=None, y=None, z=None): - if x != None and y != None and z != None: - self.x = float(x) - self.y = float(y) - self.z = float(z) - elif x != None and len(x) == 3: - self.x = float(x[0]) - self.y = float(x[1]) - self.z = float(x[2]) - elif x != None: - raise ValueError('bad initialiser') - else: - self.x = float(0) - self.y = float(0) - self.z = float(0) - - def __repr__(self): - return 'Vector3(%.2f, %.2f, %.2f)' % (self.x, - self.y, - self.z) - - def __add__(self, v): - return Vector3(self.x + v.x, - self.y + v.y, - self.z + v.z) - - __radd__ = __add__ - - def __sub__(self, v): - return Vector3(self.x - v.x, - self.y - v.y, - self.z - v.z) - - def __neg__(self): - return Vector3(-self.x, -self.y, -self.z) - - def __rsub__(self, v): - return Vector3(v.x - self.x, - v.y - self.y, - v.z - self.z) - - def __mul__(self, v): - if isinstance(v, Vector3): - '''dot product''' - return self.x*v.x + self.y*v.y + self.z*v.z - return Vector3(self.x * v, - self.y * v, - self.z * v) - - __rmul__ = __mul__ - - def __div__(self, v): - return Vector3(self.x / v, - self.y / v, - self.z / v) - - def __mod__(self, v): - '''cross product''' - return Vector3(self.y*v.z - self.z*v.y, - self.z*v.x - self.x*v.z, - self.x*v.y - self.y*v.x) - - def __copy__(self): - return Vector3(self.x, self.y, self.z) - - copy = __copy__ - - def length(self): - return sqrt(self.x**2 + self.y**2 + self.z**2) - - def zero(self): - self.x = self.y = self.z = 0 - - def angle(self, v): - '''return the angle between this vector and another vector''' - return acos(self * v) / (self.length() * v.length()) - - def normalized(self): - return self / self.length() - - def normalize(self): - v = self.normalized() - self.x = v.x - self.y = v.y - self.z = v.z - -class Matrix3: - '''a 3x3 matrix, intended as a rotation matrix''' - def __init__(self, a=None, b=None, c=None): - if a is not None and b is not None and c is not None: - self.a = a.copy() - self.b = b.copy() - self.c = c.copy() - else: - self.identity() - - def __repr__(self): - return 'Matrix3((%.2f, %.2f, %.2f), (%.2f, %.2f, %.2f), (%.2f, %.2f, %.2f))' % ( - self.a.x, self.a.y, self.a.z, - self.b.x, self.b.y, self.b.z, - self.c.x, self.c.y, self.c.z) - - def identity(self): - self.a = Vector3(1,0,0) - self.b = Vector3(0,1,0) - self.c = Vector3(0,0,1) - - def transposed(self): - return Matrix3(Vector3(self.a.x, self.b.x, self.c.x), - Vector3(self.a.y, self.b.y, self.c.y), - Vector3(self.a.z, self.b.z, self.c.z)) - - - def from_euler(self, roll, pitch, yaw): - '''fill the matrix from Euler angles in radians''' - cp = cos(pitch) - sp = sin(pitch) - sr = sin(roll) - cr = cos(roll) - sy = sin(yaw) - cy = cos(yaw) - - self.a.x = cp * cy - self.a.y = (sr * sp * cy) - (cr * sy) - self.a.z = (cr * sp * cy) + (sr * sy) - self.b.x = cp * sy - self.b.y = (sr * sp * sy) + (cr * cy) - self.b.z = (cr * sp * sy) - (sr * cy) - self.c.x = -sp - self.c.y = sr * cp - self.c.z = cr * cp - - - def to_euler(self): - '''find Euler angles for the matrix''' - if self.c.x >= 1.0: - pitch = pi - elif self.c.x <= -1.0: - pitch = -pi - else: - pitch = -asin(self.c.x) - roll = atan2(self.c.y, self.c.z) - yaw = atan2(self.b.x, self.a.x) - return (roll, pitch, yaw) - - def __add__(self, m): - return Matrix3(self.a + m.a, self.b + m.b, self.c + m.c) - - __radd__ = __add__ - - def __sub__(self, m): - return Matrix3(self.a - m.a, self.b - m.b, self.c - m.c) - - def __rsub__(self, m): - return Matrix3(m.a - self.a, m.b - self.b, m.c - self.c) - - def __mul__(self, other): - if isinstance(other, Vector3): - v = other - return Vector3(self.a.x * v.x + self.a.y * v.y + self.a.z * v.z, - self.b.x * v.x + self.b.y * v.y + self.b.z * v.z, - self.c.x * v.x + self.c.y * v.y + self.c.z * v.z) - elif isinstance(other, Matrix3): - m = other - return Matrix3(Vector3(self.a.x * m.a.x + self.a.y * m.b.x + self.a.z * m.c.x, - self.a.x * m.a.y + self.a.y * m.b.y + self.a.z * m.c.y, - self.a.x * m.a.z + self.a.y * m.b.z + self.a.z * m.c.z), - Vector3(self.b.x * m.a.x + self.b.y * m.b.x + self.b.z * m.c.x, - self.b.x * m.a.y + self.b.y * m.b.y + self.b.z * m.c.y, - self.b.x * m.a.z + self.b.y * m.b.z + self.b.z * m.c.z), - Vector3(self.c.x * m.a.x + self.c.y * m.b.x + self.c.z * m.c.x, - self.c.x * m.a.y + self.c.y * m.b.y + self.c.z * m.c.y, - self.c.x * m.a.z + self.c.y * m.b.z + self.c.z * m.c.z)) - v = other - return Matrix3(self.a * v, self.b * v, self.c * v) - - def __div__(self, v): - return Matrix3(self.a / v, self.b / v, self.c / v) - - def __neg__(self): - return Matrix3(-self.a, -self.b, -self.c) - - def __copy__(self): - return Matrix3(self.a, self.b, self.c) - - copy = __copy__ - - def rotate(self, g): - '''rotate the matrix by a given amount on 3 axes''' - temp_matrix = Matrix3() - a = self.a - b = self.b - c = self.c - temp_matrix.a.x = a.y * g.z - a.z * g.y - temp_matrix.a.y = a.z * g.x - a.x * g.z - temp_matrix.a.z = a.x * g.y - a.y * g.x - temp_matrix.b.x = b.y * g.z - b.z * g.y - temp_matrix.b.y = b.z * g.x - b.x * g.z - temp_matrix.b.z = b.x * g.y - b.y * g.x - temp_matrix.c.x = c.y * g.z - c.z * g.y - temp_matrix.c.y = c.z * g.x - c.x * g.z - temp_matrix.c.z = c.x * g.y - c.y * g.x - self.a += temp_matrix.a - self.b += temp_matrix.b - self.c += temp_matrix.c - - def normalize(self): - '''re-normalise a rotation matrix''' - error = self.a * self.b - t0 = self.a - (self.b * (0.5 * error)) - t1 = self.b - (self.a * (0.5 * error)) - t2 = t0 % t1 - self.a = t0 * (1.0 / t0.length()) - self.b = t1 * (1.0 / t1.length()) - self.c = t2 * (1.0 / t2.length()) - - def trace(self): - '''the trace of the matrix''' - return self.a.x + self.b.y + self.c.z - -def test_euler(): - '''check that from_euler() and to_euler() are consistent''' - m = Matrix3() - from math import radians, degrees - for r in range(-179, 179, 3): - for p in range(-89, 89, 3): - for y in range(-179, 179, 3): - m.from_euler(radians(r), radians(p), radians(y)) - (r2, p2, y2) = m.to_euler() - v1 = Vector3(r,p,y) - v2 = Vector3(degrees(r2),degrees(p2),degrees(y2)) - diff = v1 - v2 - if diff.length() > 1.0e-12: - print('EULER ERROR:', v1, v2, diff.length()) - -if __name__ == "__main__": - import doctest - doctest.testmod() - test_euler() - diff --git a/mavlink/share/pyshared/pymavlink/examples/sigloss.py b/mavlink/share/pyshared/pymavlink/examples/sigloss.py deleted file mode 100644 index feb189d97..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/sigloss.py +++ /dev/null @@ -1,57 +0,0 @@ -#!/usr/bin/env python - -''' -show times when signal is lost -''' - -import sys, time, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("sigloss.py [options]") -parser.add_option("--no-timestamps",dest="notimestamps", action='store_true', help="Log doesn't have timestamps") -parser.add_option("--planner",dest="planner", action='store_true', help="use planner file format") -parser.add_option("--robust",dest="robust", action='store_true', help="Enable robust parsing (skip over bad data)") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") -parser.add_option("--deltat", type='float', default=1.0, help="loss threshold in seconds") - -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 1: - print("Usage: sigloss.py [options] ") - sys.exit(1) - -def sigloss(logfile): - '''work out signal loss times for a log file''' - print("Processing log %s" % filename) - mlog = mavutil.mavlink_connection(filename, - planner_format=opts.planner, - notimestamps=opts.notimestamps, - robust_parsing=opts.robust) - - last_t = 0 - - while True: - m = mlog.recv_match() - if m is None: - return - if opts.notimestamps: - if not 'usec' in m._fieldnames: - continue - t = m.usec / 1.0e6 - else: - t = m._timestamp - if last_t != 0: - if t - last_t > opts.deltat: - print("Sig lost for %.1fs at %s" % (t-last_t, time.asctime(time.localtime(t)))) - last_t = t - -total = 0.0 -for filename in args: - sigloss(filename) diff --git a/mavlink/share/pyshared/pymavlink/examples/wptogpx.py b/mavlink/share/pyshared/pymavlink/examples/wptogpx.py deleted file mode 100644 index 306f20af2..000000000 --- a/mavlink/share/pyshared/pymavlink/examples/wptogpx.py +++ /dev/null @@ -1,69 +0,0 @@ -#!/usr/bin/env python - -''' -example program to extract GPS data from a waypoint file, and create a GPX -file, for loading into google earth -''' - -import sys, struct, time, os - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -from optparse import OptionParser -parser = OptionParser("wptogpx.py [options]") -(opts, args) = parser.parse_args() - -import mavutil, mavwp - -if len(args) < 1: - print("Usage: wptogpx.py ") - sys.exit(1) - -def wp_to_gpx(infilename, outfilename): - '''convert a wp file to a GPX file''' - - wp = mavwp.MAVWPLoader() - wp.load(infilename) - outf = open(outfilename, mode='w') - - def process_wp(w, i): - t = time.localtime(i) - outf.write(''' - %s - WP %u - -''' % (w.x, w.y, w.z, i)) - - def add_header(): - outf.write(''' - -''') - - def add_footer(): - outf.write(''' - -''') - - add_header() - - count = 0 - for i in range(wp.count()): - w = wp.wp(i) - if w.frame == 3: - w.z += wp.wp(0).z - if w.command == 16: - process_wp(w, i) - count += 1 - add_footer() - print("Created %s with %u points" % (outfilename, count)) - - -for infilename in args: - outfilename = infilename + '.gpx' - wp_to_gpx(infilename, outfilename) diff --git a/mavlink/share/pyshared/pymavlink/fgFDM.py b/mavlink/share/pyshared/pymavlink/fgFDM.py deleted file mode 100644 index f390e0a93..000000000 --- a/mavlink/share/pyshared/pymavlink/fgFDM.py +++ /dev/null @@ -1,209 +0,0 @@ -#!/usr/bin/env python -# parse and construct FlightGear NET FDM packets -# Andrew Tridgell, November 2011 -# released under GNU GPL version 2 or later - -import struct, math - -class fgFDMError(Exception): - '''fgFDM error class''' - def __init__(self, msg): - Exception.__init__(self, msg) - self.message = 'fgFDMError: ' + msg - -class fgFDMVariable(object): - '''represent a single fgFDM variable''' - def __init__(self, index, arraylength, units): - self.index = index - self.arraylength = arraylength - self.units = units - -class fgFDMVariableList(object): - '''represent a list of fgFDM variable''' - def __init__(self): - self.vars = {} - self._nextidx = 0 - - def add(self, varname, arraylength=1, units=None): - self.vars[varname] = fgFDMVariable(self._nextidx, arraylength, units=units) - self._nextidx += arraylength - -class fgFDM(object): - '''a flightgear native FDM parser/generator''' - def __init__(self): - '''init a fgFDM object''' - self.FG_NET_FDM_VERSION = 24 - self.pack_string = '>I 4x 3d 6f 11f 3f 2f I 4I 4f 4f 4f 4f 4f 4f 4f 4f 4f I 4f I 3I 3f 3f 3f I i f 10f' - self.values = [0]*98 - - self.FG_MAX_ENGINES = 4 - self.FG_MAX_WHEELS = 3 - self.FG_MAX_TANKS = 4 - - # supported unit mappings - self.unitmap = { - ('radians', 'degrees') : math.degrees(1), - ('rps', 'dps') : math.degrees(1), - ('feet', 'meters') : 0.3048, - ('fps', 'mps') : 0.3048, - ('knots', 'mps') : 0.514444444, - ('knots', 'fps') : 0.514444444/0.3048, - ('fpss', 'mpss') : 0.3048, - ('seconds', 'minutes') : 60, - ('seconds', 'hours') : 3600, - } - - # build a mapping between variable name and index in the values array - # note that the order of this initialisation is critical - it must - # match the wire structure - self.mapping = fgFDMVariableList() - self.mapping.add('version') - - # position - self.mapping.add('longitude', units='radians') # geodetic (radians) - self.mapping.add('latitude', units='radians') # geodetic (radians) - self.mapping.add('altitude', units='meters') # above sea level (meters) - self.mapping.add('agl', units='meters') # above ground level (meters) - - # attitude - self.mapping.add('phi', units='radians') # roll (radians) - self.mapping.add('theta', units='radians') # pitch (radians) - self.mapping.add('psi', units='radians') # yaw or true heading (radians) - self.mapping.add('alpha', units='radians') # angle of attack (radians) - self.mapping.add('beta', units='radians') # side slip angle (radians) - - # Velocities - self.mapping.add('phidot', units='rps') # roll rate (radians/sec) - self.mapping.add('thetadot', units='rps') # pitch rate (radians/sec) - self.mapping.add('psidot', units='rps') # yaw rate (radians/sec) - self.mapping.add('vcas', units='fps') # calibrated airspeed - self.mapping.add('climb_rate', units='fps') # feet per second - self.mapping.add('v_north', units='fps') # north velocity in local/body frame, fps - self.mapping.add('v_east', units='fps') # east velocity in local/body frame, fps - self.mapping.add('v_down', units='fps') # down/vertical velocity in local/body frame, fps - self.mapping.add('v_wind_body_north', units='fps') # north velocity in local/body frame - self.mapping.add('v_wind_body_east', units='fps') # east velocity in local/body frame - self.mapping.add('v_wind_body_down', units='fps') # down/vertical velocity in local/body - - # Accelerations - self.mapping.add('A_X_pilot', units='fpss') # X accel in body frame ft/sec^2 - self.mapping.add('A_Y_pilot', units='fpss') # Y accel in body frame ft/sec^2 - self.mapping.add('A_Z_pilot', units='fpss') # Z accel in body frame ft/sec^2 - - # Stall - self.mapping.add('stall_warning') # 0.0 - 1.0 indicating the amount of stall - self.mapping.add('slip_deg', units='degrees') # slip ball deflection - - # Engine status - self.mapping.add('num_engines') # Number of valid engines - self.mapping.add('eng_state', self.FG_MAX_ENGINES) # Engine state (off, cranking, running) - self.mapping.add('rpm', self.FG_MAX_ENGINES) # Engine RPM rev/min - self.mapping.add('fuel_flow', self.FG_MAX_ENGINES) # Fuel flow gallons/hr - self.mapping.add('fuel_px', self.FG_MAX_ENGINES) # Fuel pressure psi - self.mapping.add('egt', self.FG_MAX_ENGINES) # Exhuast gas temp deg F - self.mapping.add('cht', self.FG_MAX_ENGINES) # Cylinder head temp deg F - self.mapping.add('mp_osi', self.FG_MAX_ENGINES) # Manifold pressure - self.mapping.add('tit', self.FG_MAX_ENGINES) # Turbine Inlet Temperature - self.mapping.add('oil_temp', self.FG_MAX_ENGINES) # Oil temp deg F - self.mapping.add('oil_px', self.FG_MAX_ENGINES) # Oil pressure psi - - # Consumables - self.mapping.add('num_tanks') # Max number of fuel tanks - self.mapping.add('fuel_quantity', self.FG_MAX_TANKS) - - # Gear status - self.mapping.add('num_wheels') - self.mapping.add('wow', self.FG_MAX_WHEELS) - self.mapping.add('gear_pos', self.FG_MAX_WHEELS) - self.mapping.add('gear_steer', self.FG_MAX_WHEELS) - self.mapping.add('gear_compression', self.FG_MAX_WHEELS) - - # Environment - self.mapping.add('cur_time', units='seconds') # current unix time - self.mapping.add('warp', units='seconds') # offset in seconds to unix time - self.mapping.add('visibility', units='meters') # visibility in meters (for env. effects) - - # Control surface positions (normalized values) - self.mapping.add('elevator') - self.mapping.add('elevator_trim_tab') - self.mapping.add('left_flap') - self.mapping.add('right_flap') - self.mapping.add('left_aileron') - self.mapping.add('right_aileron') - self.mapping.add('rudder') - self.mapping.add('nose_wheel') - self.mapping.add('speedbrake') - self.mapping.add('spoilers') - - self._packet_size = struct.calcsize(self.pack_string) - - self.set('version', self.FG_NET_FDM_VERSION) - - if len(self.values) != self.mapping._nextidx: - raise fgFDMError('Invalid variable list in initialisation') - - def packet_size(self): - '''return expected size of FG FDM packets''' - return self._packet_size - - def convert(self, value, fromunits, tounits): - '''convert a value from one set of units to another''' - if fromunits == tounits: - return value - if (fromunits,tounits) in self.unitmap: - return value * self.unitmap[(fromunits,tounits)] - if (tounits,fromunits) in self.unitmap: - return value / self.unitmap[(tounits,fromunits)] - raise fgFDMError("unknown unit mapping (%s,%s)" % (fromunits, tounits)) - - - def units(self, varname): - '''return the default units of a variable''' - if not varname in self.mapping.vars: - raise fgFDMError('Unknown variable %s' % varname) - return self.mapping.vars[varname].units - - - def variables(self): - '''return a list of available variables''' - return sorted(self.mapping.vars.keys(), - key = lambda v : self.mapping.vars[v].index) - - - def get(self, varname, idx=0, units=None): - '''get a variable value''' - if not varname in self.mapping.vars: - raise fgFDMError('Unknown variable %s' % varname) - if idx >= self.mapping.vars[varname].arraylength: - raise fgFDMError('index of %s beyond end of array idx=%u arraylength=%u' % ( - varname, idx, self.mapping.vars[varname].arraylength)) - value = self.values[self.mapping.vars[varname].index + idx] - if units: - value = self.convert(value, self.mapping.vars[varname].units, units) - return value - - def set(self, varname, value, idx=0, units=None): - '''set a variable value''' - if not varname in self.mapping.vars: - raise fgFDMError('Unknown variable %s' % varname) - if idx >= self.mapping.vars[varname].arraylength: - raise fgFDMError('index of %s beyond end of array idx=%u arraylength=%u' % ( - varname, idx, self.mapping.vars[varname].arraylength)) - if units: - value = self.convert(value, units, self.mapping.vars[varname].units) - self.values[self.mapping.vars[varname].index + idx] = value - - def parse(self, buf): - '''parse a FD FDM buffer''' - try: - t = struct.unpack(self.pack_string, buf) - except struct.error, msg: - raise fgFDMError('unable to parse - %s' % msg) - self.values = list(t) - - def pack(self): - '''pack a FD FDM buffer from current values''' - for i in range(len(self.values)): - if math.isnan(self.values[i]): - self.values[i] = 0 - return struct.pack(self.pack_string, *self.values) diff --git a/mavlink/share/pyshared/pymavlink/generator/.gitignore b/mavlink/share/pyshared/pymavlink/generator/.gitignore deleted file mode 100644 index 0d20b6487..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/.gitignore +++ /dev/null @@ -1 +0,0 @@ -*.pyc diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h deleted file mode 100644 index b70991f5a..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/checksum.h +++ /dev/null @@ -1,89 +0,0 @@ -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef _CHECKSUM_H_ -#define _CHECKSUM_H_ - - -/** - * - * CALCULATE THE CHECKSUM - * - */ - -#define X25_INIT_CRC 0xffff -#define X25_VALIDATE_CRC 0xf0b8 - -/** - * @brief Accumulate the X.25 CRC by adding one char at a time. - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new char to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum) -{ - /*Accumulate one byte of data into the CRC*/ - uint8_t tmp; - - tmp = data ^ (uint8_t)(*crcAccum &0xff); - tmp ^= (tmp<<4); - *crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); -} - -/** - * @brief Initiliaze the buffer for the X.25 CRC - * - * @param crcAccum the 16 bit X.25 CRC - */ -static inline void crc_init(uint16_t* crcAccum) -{ - *crcAccum = X25_INIT_CRC; -} - - -/** - * @brief Calculates the X.25 checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate(uint8_t* pBuffer, uint16_t length) -{ - uint16_t crcTmp; - crc_init(&crcTmp); - while (length--) { - crc_accumulate(*pBuffer++, &crcTmp); - } - return crcTmp; -} - -/** - * @brief Accumulate the X.25 CRC by adding an array of bytes - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new bytes to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length) -{ - const uint8_t *p = (const uint8_t *)pBuffer; - while (length--) { - crc_accumulate(*p++, crcAccum); - } -} - - - - -#endif /* _CHECKSUM_H_ */ - -#ifdef __cplusplus -} -#endif diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h deleted file mode 100644 index 98250e1ac..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_helpers.h +++ /dev/null @@ -1,488 +0,0 @@ -#ifndef _MAVLINK_HELPERS_H_ -#define _MAVLINK_HELPERS_H_ - -#include "string.h" -#include "checksum.h" -#include "mavlink_types.h" - -#ifndef MAVLINK_HELPER -#define MAVLINK_HELPER -#endif - -/* - internal function to give access to the channel status for each channel - */ -MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) -{ - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; - return &m_mavlink_status[chan]; -} - -/** - * @brief Finalize a MAVLink message with channel assignment - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. This function - * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack - * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. - * - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length) -#endif -{ - // This code part is the same for all messages; - uint16_t checksum; - msg->magic = MAVLINK_STX; - msg->len = length; - msg->sysid = system_id; - msg->compid = component_id; - // One sequence number per component - msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; - mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; - checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); -#endif - mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF); - mavlink_ck_b(msg) = (uint8_t)(checksum >> 8); - - return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - - -/** - * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length, uint8_t crc_extra) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); -} -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); -} -#endif - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); - -/** - * @brief Finalize a MAVLink message with channel assignment and send - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, - uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) -#endif -{ - uint16_t checksum; - uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; - uint8_t ck[2]; - mavlink_status_t *status = mavlink_get_channel_status(chan); - buf[0] = MAVLINK_STX; - buf[1] = length; - buf[2] = status->current_tx_seq; - buf[3] = mavlink_system.sysid; - buf[4] = mavlink_system.compid; - buf[5] = msgid; - status->current_tx_seq++; - checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); - crc_accumulate_buffer(&checksum, packet, length); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); -#endif - ck[0] = (uint8_t)(checksum & 0xFF); - ck[1] = (uint8_t)(checksum >> 8); - - MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); - _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); - _mavlink_send_uart(chan, packet, length); - _mavlink_send_uart(chan, (const char *)ck, 2); - MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -/** - * @brief Pack a message to send it over a serial byte stream - */ -MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) -{ - memcpy(buffer, (uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); - return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; -} - -union __mavlink_bitfield { - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; -}; - - -MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) -{ - crc_init(&msg->checksum); -} - -MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) -{ - crc_accumulate(c, &msg->checksum); -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. Checksum and other failures will be silently - * ignored. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to barse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @return 0 if no message could be decoded, 1 else - * - * A typical use scenario of this function call is: - * - * @code - * #include // For fixed-width uint8_t type - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg)) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - static mavlink_message_t m_mavlink_message[MAVLINK_COMM_NUM_BUFFERS]; - - /* - default message crc function. You can override this per-system to - put this data in a different memory segment - */ -#if MAVLINK_CRC_EXTRA -#ifndef MAVLINK_MESSAGE_CRC - static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; -#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] -#endif -#endif - - mavlink_message_t* rxmsg = &m_mavlink_message[chan]; ///< The currently decoded message - mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status - int bufferIndex = 0; - - status->msg_received = 0; - - switch (status->parse_state) - { - case MAVLINK_PARSE_STATE_UNINIT: - case MAVLINK_PARSE_STATE_IDLE: - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - break; - - case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received - /* Support shorter buffers than the - default maximum packet size */ -#if (MAVLINK_MAX_PAYLOAD_LEN < 255) - || c > MAVLINK_MAX_PAYLOAD_LEN -#endif - ) - { - status->buffer_overrun++; - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - } - else - { - // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 - rxmsg->len = c; - status->packet_idx = 0; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; - } - break; - - case MAVLINK_PARSE_STATE_GOT_LENGTH: - rxmsg->seq = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; - break; - - case MAVLINK_PARSE_STATE_GOT_SEQ: - rxmsg->sysid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; - break; - - case MAVLINK_PARSE_STATE_GOT_SYSID: - rxmsg->compid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPID: - rxmsg->msgid = c; - mavlink_update_checksum(rxmsg, c); - if (rxmsg->len == 0) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; - } - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID: - _MAV_PAYLOAD(rxmsg)[status->packet_idx++] = (char)c; - mavlink_update_checksum(rxmsg, c); - if (status->packet_idx == rxmsg->len) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - break; - - case MAVLINK_PARSE_STATE_GOT_PAYLOAD: -#if MAVLINK_CRC_EXTRA - mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); -#endif - if (c != (rxmsg->checksum & 0xFF)) { - // Check first checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; - } - break; - - case MAVLINK_PARSE_STATE_GOT_CRC1: - if (c != (rxmsg->checksum >> 8)) { - // Check second checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - } - else - { - // Successfully got message - status->msg_received = 1; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - } - break; - } - - bufferIndex++; - // If a message has been sucessfully decoded, check index - if (status->msg_received == 1) - { - //while(status->current_seq != rxmsg->seq) - //{ - // status->packet_rx_drop_count++; - // status->current_seq++; - //} - status->current_rx_seq = rxmsg->seq; - // Initial condition: If no packet has been received so far, drop count is undefined - if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; - // Count this packet as received - status->packet_rx_success_count++; - } - - r_mavlink_status->current_rx_seq = status->current_rx_seq+1; - r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; - r_mavlink_status->packet_rx_drop_count = status->parse_error; - status->parse_error = 0; - return status->msg_received; -} - -/** - * @brief Put a bitfield of length 1-32 bit into the buffer - * - * @param b the value to add, will be encoded in the bitfield - * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. - * @param packet_index the position in the packet (the index of the first byte to use) - * @param bit_index the position in the byte (the index of the first bit to use) - * @param buffer packet buffer to write into - * @return new position of the last used byte in the buffer - */ -MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) -{ - uint16_t bits_remain = bits; - // Transform number into network order - int32_t v; - uint8_t i_bit_index, i_byte_index, curr_bits_n; -#if MAVLINK_NEED_BYTE_SWAP - union { - int32_t i; - uint8_t b[4]; - } bin, bout; - bin.i = b; - bout.b[0] = bin.b[3]; - bout.b[1] = bin.b[2]; - bout.b[2] = bin.b[1]; - bout.b[3] = bin.b[0]; - v = bout.i; -#else - v = b; -#endif - - // buffer in - // 01100000 01000000 00000000 11110001 - // buffer out - // 11110001 00000000 01000000 01100000 - - // Existing partly filled byte (four free slots) - // 0111xxxx - - // Mask n free bits - // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 - // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 - - // Shift n bits into the right position - // out = in >> n; - - // Mask and shift bytes - i_bit_index = bit_index; - i_byte_index = packet_index; - if (bit_index > 0) - { - // If bits were available at start, they were available - // in the byte before the current index - i_byte_index--; - } - - // While bits have not been packed yet - while (bits_remain > 0) - { - // Bits still have to be packed - // there can be more than 8 bits, so - // we might have to pack them into more than one byte - - // First pack everything we can into the current 'open' byte - //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 - //FIXME - if (bits_remain <= (uint8_t)(8 - i_bit_index)) - { - // Enough space - curr_bits_n = (uint8_t)bits_remain; - } - else - { - curr_bits_n = (8 - i_bit_index); - } - - // Pack these n bits into the current byte - // Mask out whatever was at that position with ones (xxx11111) - buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); - // Put content to this position, by masking out the non-used part - buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); - - // Increment the bit index - i_bit_index += curr_bits_n; - - // Now proceed to the next byte, if necessary - bits_remain -= curr_bits_n; - if (bits_remain > 0) - { - // Offer another 8 bits / one byte - i_byte_index++; - i_bit_index = 0; - } - } - - *r_bit_index = i_bit_index; - // If a partly filled byte is present, mark this as consumed - if (i_bit_index != 7) i_byte_index++; - return i_byte_index - packet_index; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -// To make MAVLink work on your MCU, define comm_send_ch() if you wish -// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a -// whole packet at a time - -/* - -#include "mavlink_types.h" - -void comm_send_ch(mavlink_channel_t chan, uint8_t ch) -{ - if (chan == MAVLINK_COMM_0) - { - uart0_transmit(ch); - } - if (chan == MAVLINK_COMM_1) - { - uart1_transmit(ch); - } -} - */ - -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) -{ -#ifdef MAVLINK_SEND_UART_BYTES - /* this is the more efficient approach, if the platform - defines it */ - MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len); -#else - /* fallback to one byte at a time */ - uint16_t i; - for (i = 0; i < len; i++) { - comm_send_ch(chan, (uint8_t)buf[i]); - } -#endif -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h deleted file mode 100644 index 630cb84b7..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/mavlink_types.h +++ /dev/null @@ -1,300 +0,0 @@ -#ifndef MAVLINK_TYPES_H_ -#define MAVLINK_TYPES_H_ - -#include "inttypes.h" - -enum MAV_CLASS -{ - MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything - MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch - MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu - MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com - MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org - MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints - MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands - MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set - MAV_CLASS_NONE = 8, ///< No valid autopilot - MAV_CLASS_NB ///< Number of autopilot classes -}; - -enum MAV_ACTION -{ - MAV_ACTION_HOLD = 0, - MAV_ACTION_MOTORS_START = 1, - MAV_ACTION_LAUNCH = 2, - MAV_ACTION_RETURN = 3, - MAV_ACTION_EMCY_LAND = 4, - MAV_ACTION_EMCY_KILL = 5, - MAV_ACTION_CONFIRM_KILL = 6, - MAV_ACTION_CONTINUE = 7, - MAV_ACTION_MOTORS_STOP = 8, - MAV_ACTION_HALT = 9, - MAV_ACTION_SHUTDOWN = 10, - MAV_ACTION_REBOOT = 11, - MAV_ACTION_SET_MANUAL = 12, - MAV_ACTION_SET_AUTO = 13, - MAV_ACTION_STORAGE_READ = 14, - MAV_ACTION_STORAGE_WRITE = 15, - MAV_ACTION_CALIBRATE_RC = 16, - MAV_ACTION_CALIBRATE_GYRO = 17, - MAV_ACTION_CALIBRATE_MAG = 18, - MAV_ACTION_CALIBRATE_ACC = 19, - MAV_ACTION_CALIBRATE_PRESSURE = 20, - MAV_ACTION_REC_START = 21, - MAV_ACTION_REC_PAUSE = 22, - MAV_ACTION_REC_STOP = 23, - MAV_ACTION_TAKEOFF = 24, - MAV_ACTION_NAVIGATE = 25, - MAV_ACTION_LAND = 26, - MAV_ACTION_LOITER = 27, - MAV_ACTION_SET_ORIGIN = 28, - MAV_ACTION_RELAY_ON = 29, - MAV_ACTION_RELAY_OFF = 30, - MAV_ACTION_GET_IMAGE = 31, - MAV_ACTION_VIDEO_START = 32, - MAV_ACTION_VIDEO_STOP = 33, - MAV_ACTION_RESET_MAP = 34, - MAV_ACTION_RESET_PLAN = 35, - MAV_ACTION_DELAY_BEFORE_COMMAND = 36, - MAV_ACTION_ASCEND_AT_RATE = 37, - MAV_ACTION_CHANGE_MODE = 38, - MAV_ACTION_LOITER_MAX_TURNS = 39, - MAV_ACTION_LOITER_MAX_TIME = 40, - MAV_ACTION_START_HILSIM = 41, - MAV_ACTION_STOP_HILSIM = 42, - MAV_ACTION_NB ///< Number of MAV actions -}; - -enum MAV_MODE -{ - MAV_MODE_UNINIT = 0, ///< System is in undefined state - MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe - MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control - MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint - MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation - MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use - MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use - MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use - MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive - MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back -}; - -enum MAV_STATE -{ - MAV_STATE_UNINIT = 0, - MAV_STATE_BOOT, - MAV_STATE_CALIBRATING, - MAV_STATE_STANDBY, - MAV_STATE_ACTIVE, - MAV_STATE_CRITICAL, - MAV_STATE_EMERGENCY, - MAV_STATE_HILSIM, - MAV_STATE_POWEROFF -}; - -enum MAV_NAV -{ - MAV_NAV_GROUNDED = 0, - MAV_NAV_LIFTOFF, - MAV_NAV_HOLD, - MAV_NAV_WAYPOINT, - MAV_NAV_VECTOR, - MAV_NAV_RETURNING, - MAV_NAV_LANDING, - MAV_NAV_LOST, - MAV_NAV_LOITER, - MAV_NAV_FREE_DRIFT -}; - -enum MAV_TYPE -{ - MAV_GENERIC = 0, - MAV_FIXED_WING = 1, - MAV_QUADROTOR = 2, - MAV_COAXIAL = 3, - MAV_HELICOPTER = 4, - MAV_GROUND = 5, - OCU = 6, - MAV_AIRSHIP = 7, - MAV_FREE_BALLOON = 8, - MAV_ROCKET = 9, - UGV_GROUND_ROVER = 10, - UGV_SURFACE_SHIP = 11 -}; - -enum MAV_AUTOPILOT_TYPE -{ - MAV_AUTOPILOT_GENERIC = 0, - MAV_AUTOPILOT_PIXHAWK = 1, - MAV_AUTOPILOT_SLUGS = 2, - MAV_AUTOPILOT_ARDUPILOTMEGA = 3, - MAV_AUTOPILOT_NONE = 4 -}; - -enum MAV_COMPONENT -{ - MAV_COMP_ID_GPS, - MAV_COMP_ID_WAYPOINTPLANNER, - MAV_COMP_ID_BLOBTRACKER, - MAV_COMP_ID_PATHPLANNER, - MAV_COMP_ID_AIRSLAM, - MAV_COMP_ID_MAPPER, - MAV_COMP_ID_CAMERA, - MAV_COMP_ID_RADIO = 68, - MAV_COMP_ID_IMU = 200, - MAV_COMP_ID_IMU_2 = 201, - MAV_COMP_ID_IMU_3 = 202, - MAV_COMP_ID_UDP_BRIDGE = 240, - MAV_COMP_ID_UART_BRIDGE = 241, - MAV_COMP_ID_SYSTEM_CONTROL = 250 -}; - -enum MAV_FRAME -{ - MAV_FRAME_GLOBAL = 0, - MAV_FRAME_LOCAL = 1, - MAV_FRAME_MISSION = 2, - MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, - MAV_FRAME_LOCAL_ENU = 4 -}; - -enum MAVLINK_DATA_STREAM_TYPE -{ - MAVLINK_DATA_STREAM_IMG_JPEG, - MAVLINK_DATA_STREAM_IMG_BMP, - MAVLINK_DATA_STREAM_IMG_RAW8U, - MAVLINK_DATA_STREAM_IMG_RAW32U, - MAVLINK_DATA_STREAM_IMG_PGM, - MAVLINK_DATA_STREAM_IMG_PNG -}; - -#ifndef MAVLINK_MAX_PAYLOAD_LEN -// it is possible to override this, but be careful! -#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length -#endif - -#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) -#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum -#define MAVLINK_NUM_CHECKSUM_BYTES 2 -#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) - -#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length - -typedef struct param_union { - union { - float param_float; - int32_t param_int32; - uint32_t param_uint32; - }; - uint8_t type; -} mavlink_param_union_t; - -typedef struct __mavlink_system { - uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t type; ///< Unused, can be used by user to store the system's type - uint8_t state; ///< Unused, can be used by user to store the system's state - uint8_t mode; ///< Unused, can be used by user to store the system's mode - uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode -} mavlink_system_t; - -typedef struct __mavlink_message { - uint16_t checksum; /// sent at end of packet - uint8_t magic; ///< protocol magic marker - uint8_t len; ///< Length of payload - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint8_t msgid; ///< ID of message in payload - uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; -} mavlink_message_t; - -typedef enum { - MAVLINK_TYPE_CHAR = 0, - MAVLINK_TYPE_UINT8_T = 1, - MAVLINK_TYPE_INT8_T = 2, - MAVLINK_TYPE_UINT16_T = 3, - MAVLINK_TYPE_INT16_T = 4, - MAVLINK_TYPE_UINT32_T = 5, - MAVLINK_TYPE_INT32_T = 6, - MAVLINK_TYPE_UINT64_T = 7, - MAVLINK_TYPE_INT64_T = 8, - MAVLINK_TYPE_FLOAT = 9, - MAVLINK_TYPE_DOUBLE = 10 -} mavlink_message_type_t; - -#define MAVLINK_MAX_FIELDS 64 - -typedef struct __mavlink_field_info { - const char *name; // name of this field - const char *print_format; // printing format hint, or NULL - mavlink_message_type_t type; // type of this field - unsigned array_length; // if non-zero, field is an array - unsigned wire_offset; // offset of each field in the payload - unsigned structure_offset; // offset in a C structure -} mavlink_field_info_t; - -// note that in this structure the order of fields is the order -// in the XML file, not necessary the wire order -typedef struct __mavlink_message_info { - const char *name; // name of the message - unsigned num_fields; // how many fields in this message - mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information -} mavlink_message_info_t; - -#define _MAV_PAYLOAD(msg) ((char *)(&(msg)->payload64[0])) -#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) - -// checksum is immediately after the payload bytes -#define mavlink_ck_a(msg) *(msg->len + (uint8_t *)_MAV_PAYLOAD(msg)) -#define mavlink_ck_b(msg) *((msg->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD(msg)) - -typedef enum { - MAVLINK_COMM_0, - MAVLINK_COMM_1, - MAVLINK_COMM_2, - MAVLINK_COMM_3 -} mavlink_channel_t; - -/* - * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number - * of buffers they will use. If more are used, then the result will be - * a stack overrun - */ -#ifndef MAVLINK_COMM_NUM_BUFFERS -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) -# define MAVLINK_COMM_NUM_BUFFERS 16 -#else -# define MAVLINK_COMM_NUM_BUFFERS 4 -#endif -#endif - -typedef enum { - MAVLINK_PARSE_STATE_UNINIT=0, - MAVLINK_PARSE_STATE_IDLE, - MAVLINK_PARSE_STATE_GOT_STX, - MAVLINK_PARSE_STATE_GOT_SEQ, - MAVLINK_PARSE_STATE_GOT_LENGTH, - MAVLINK_PARSE_STATE_GOT_SYSID, - MAVLINK_PARSE_STATE_GOT_COMPID, - MAVLINK_PARSE_STATE_GOT_MSGID, - MAVLINK_PARSE_STATE_GOT_PAYLOAD, - MAVLINK_PARSE_STATE_GOT_CRC1 -} mavlink_parse_state_t; ///< The state machine for the comm parser - -typedef struct __mavlink_status { - uint8_t msg_received; ///< Number of received messages - uint8_t buffer_overrun; ///< Number of buffer overruns - uint8_t parse_error; ///< Number of parse errors - mavlink_parse_state_t parse_state; ///< Parsing state machine - uint8_t packet_idx; ///< Index in current packet - uint8_t current_rx_seq; ///< Sequence number of last packet received - uint8_t current_tx_seq; ///< Sequence number of last packet sent - uint16_t packet_rx_success_count; ///< Received packets - uint16_t packet_rx_drop_count; ///< Number of packet drops -} mavlink_status_t; - -#define MAVLINK_BIG_ENDIAN 0 -#define MAVLINK_LITTLE_ENDIAN 1 - -#endif /* MAVLINK_TYPES_H_ */ diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h deleted file mode 100644 index 05195c369..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/protocol.h +++ /dev/null @@ -1,319 +0,0 @@ -#ifndef _MAVLINK_PROTOCOL_H_ -#define _MAVLINK_PROTOCOL_H_ - -#include "string.h" -#include "mavlink_types.h" - -/* - If you want MAVLink on a system that is native big-endian, - you need to define NATIVE_BIG_ENDIAN -*/ -#ifdef NATIVE_BIG_ENDIAN -# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) -#else -# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) -#endif - -#ifndef MAVLINK_STACK_BUFFER -#define MAVLINK_STACK_BUFFER 0 -#endif - -#ifndef MAVLINK_AVOID_GCC_STACK_BUG -# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) -#endif - -#ifndef MAVLINK_ASSERT -#define MAVLINK_ASSERT(x) -#endif - -#ifndef MAVLINK_START_UART_SEND -#define MAVLINK_START_UART_SEND(chan, length) -#endif - -#ifndef MAVLINK_END_UART_SEND -#define MAVLINK_END_UART_SEND(chan, length) -#endif - -#ifdef MAVLINK_SEPARATE_HELPERS -#define MAVLINK_HELPER -#else -#define MAVLINK_HELPER static inline -#include "mavlink_helpers.h" -#endif // MAVLINK_SEPARATE_HELPERS - -/* always include the prototypes to ensure we don't get out of sync */ -MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length, uint8_t crc_extra); -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length, uint8_t crc_extra); -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, - uint8_t length, uint8_t crc_extra); -#endif -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length); -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length); -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length); -#endif // MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); -MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); -MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c); -MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); -MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, - uint8_t* r_bit_index, uint8_t* buffer); -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); -#endif - -/** - * @brief Get the required buffer size for this message - */ -static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) -{ - return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - -#if MAVLINK_NEED_BYTE_SWAP -static inline void byte_swap_2(char *dst, const char *src) -{ - dst[0] = src[1]; - dst[1] = src[0]; -} -static inline void byte_swap_4(char *dst, const char *src) -{ - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; -} -static inline void byte_swap_8(char *dst, const char *src) -{ - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; -} -#elif !MAVLINK_ALIGNED_FIELDS -static inline void byte_copy_2(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; -} -static inline void byte_copy_4(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; - dst[2] = src[2]; - dst[3] = src[3]; -} -static inline void byte_copy_8(char *dst, const char *src) -{ - memcpy(dst, src, 8); -} -#endif - -#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b -#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b -#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b - -#if MAVLINK_NEED_BYTE_SWAP -#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#elif !MAVLINK_ALIGNED_FIELDS -#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#else -#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b -#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b -#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b -#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b -#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b -#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b -#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b -#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b -#endif - -/* - like memcpy(), but if src is NULL, do a memset to zero - */ -static void mav_array_memcpy(void *dest, const void *src, size_t n) -{ - if (src == NULL) { - memset(dest, 0, n); - } else { - memcpy(dest, src, n); - } -} - -/* - * Place a char array into a buffer - */ -static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); -} - -/* - * Place a uint8_t array into a buffer - */ -static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); -} - -/* - * Place a int8_t array into a buffer - */ -static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); -} - -#if MAVLINK_NEED_BYTE_SWAP -#define _MAV_PUT_ARRAY(TYPE, V) \ -static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ -{ \ - if (b == NULL) { \ - memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ - } else { \ - uint16_t i; \ - for (i=0; imsgid = MAVLINK_MSG_ID_TEST_TYPES; - return mavlink_finalize_message(msg, system_id, component_id, 179); -} - -/** - * @brief Pack a test_types message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message was sent over - * @param msg The MAVLink message to compress the data into - * @param c char - * @param s string - * @param u8 uint8_t - * @param u16 uint16_t - * @param u32 uint32_t - * @param u64 uint64_t - * @param s8 int8_t - * @param s16 int16_t - * @param s32 int32_t - * @param s64 int64_t - * @param f float - * @param d double - * @param u8_array uint8_t_array - * @param u16_array uint16_t_array - * @param u32_array uint32_t_array - * @param u64_array uint64_t_array - * @param s8_array int8_t_array - * @param s16_array int16_t_array - * @param s32_array int32_t_array - * @param s64_array int64_t_array - * @param f_array float_array - * @param d_array double_array - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[179]; - _mav_put_char(buf, 0, c); - _mav_put_uint8_t(buf, 11, u8); - _mav_put_uint16_t(buf, 12, u16); - _mav_put_uint32_t(buf, 14, u32); - _mav_put_uint64_t(buf, 18, u64); - _mav_put_int8_t(buf, 26, s8); - _mav_put_int16_t(buf, 27, s16); - _mav_put_int32_t(buf, 29, s32); - _mav_put_int64_t(buf, 33, s64); - _mav_put_float(buf, 41, f); - _mav_put_double(buf, 45, d); - _mav_put_char_array(buf, 1, s, 10); - _mav_put_uint8_t_array(buf, 53, u8_array, 3); - _mav_put_uint16_t_array(buf, 56, u16_array, 3); - _mav_put_uint32_t_array(buf, 62, u32_array, 3); - _mav_put_uint64_t_array(buf, 74, u64_array, 3); - _mav_put_int8_t_array(buf, 98, s8_array, 3); - _mav_put_int16_t_array(buf, 101, s16_array, 3); - _mav_put_int32_t_array(buf, 107, s32_array, 3); - _mav_put_int64_t_array(buf, 119, s64_array, 3); - _mav_put_float_array(buf, 143, f_array, 3); - _mav_put_double_array(buf, 155, d_array, 3); - memcpy(_MAV_PAYLOAD(msg), buf, 179); -#else - mavlink_test_types_t packet; - packet.c = c; - packet.u8 = u8; - packet.u16 = u16; - packet.u32 = u32; - packet.u64 = u64; - packet.s8 = s8; - packet.s16 = s16; - packet.s32 = s32; - packet.s64 = s64; - packet.f = f; - packet.d = d; - mav_array_memcpy(packet.s, s, sizeof(char)*10); - mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); - mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); - mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); - mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); - mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); - mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); - mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); - mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); - mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); - mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); - memcpy(_MAV_PAYLOAD(msg), &packet, 179); -#endif - - msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 179); -} - -/** - * @brief Encode a test_types struct into a message - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param test_types C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types) -{ - return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array); -} - -/** - * @brief Send a test_types message - * @param chan MAVLink channel to send the message - * - * @param c char - * @param s string - * @param u8 uint8_t - * @param u16 uint16_t - * @param u32 uint32_t - * @param u64 uint64_t - * @param s8 int8_t - * @param s16 int16_t - * @param s32 int32_t - * @param s64 int64_t - * @param f float - * @param d double - * @param u8_array uint8_t_array - * @param u16_array uint16_t_array - * @param u32_array uint32_t_array - * @param u64_array uint64_t_array - * @param s8_array int8_t_array - * @param s16_array int16_t_array - * @param s32_array int32_t_array - * @param s64_array int64_t_array - * @param f_array float_array - * @param d_array double_array - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[179]; - _mav_put_char(buf, 0, c); - _mav_put_uint8_t(buf, 11, u8); - _mav_put_uint16_t(buf, 12, u16); - _mav_put_uint32_t(buf, 14, u32); - _mav_put_uint64_t(buf, 18, u64); - _mav_put_int8_t(buf, 26, s8); - _mav_put_int16_t(buf, 27, s16); - _mav_put_int32_t(buf, 29, s32); - _mav_put_int64_t(buf, 33, s64); - _mav_put_float(buf, 41, f); - _mav_put_double(buf, 45, d); - _mav_put_char_array(buf, 1, s, 10); - _mav_put_uint8_t_array(buf, 53, u8_array, 3); - _mav_put_uint16_t_array(buf, 56, u16_array, 3); - _mav_put_uint32_t_array(buf, 62, u32_array, 3); - _mav_put_uint64_t_array(buf, 74, u64_array, 3); - _mav_put_int8_t_array(buf, 98, s8_array, 3); - _mav_put_int16_t_array(buf, 101, s16_array, 3); - _mav_put_int32_t_array(buf, 107, s32_array, 3); - _mav_put_int64_t_array(buf, 119, s64_array, 3); - _mav_put_float_array(buf, 143, f_array, 3); - _mav_put_double_array(buf, 155, d_array, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179); -#else - mavlink_test_types_t packet; - packet.c = c; - packet.u8 = u8; - packet.u16 = u16; - packet.u32 = u32; - packet.u64 = u64; - packet.s8 = s8; - packet.s16 = s16; - packet.s32 = s32; - packet.s64 = s64; - packet.f = f; - packet.d = d; - mav_array_memcpy(packet.s, s, sizeof(char)*10); - mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); - mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); - mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); - mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); - mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); - mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); - mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); - mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); - mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); - mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179); -#endif -} - -#endif - -// MESSAGE TEST_TYPES UNPACKING - - -/** - * @brief Get field c from test_types message - * - * @return char - */ -static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg) -{ - return _MAV_RETURN_char(msg, 0); -} - -/** - * @brief Get field s from test_types message - * - * @return string - */ -static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s) -{ - return _MAV_RETURN_char_array(msg, s, 10, 1); -} - -/** - * @brief Get field u8 from test_types message - * - * @return uint8_t - */ -static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 11); -} - -/** - * @brief Get field u16 from test_types message - * - * @return uint16_t - */ -static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 12); -} - -/** - * @brief Get field u32 from test_types message - * - * @return uint32_t - */ -static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 14); -} - -/** - * @brief Get field u64 from test_types message - * - * @return uint64_t - */ -static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 18); -} - -/** - * @brief Get field s8 from test_types message - * - * @return int8_t - */ -static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 26); -} - -/** - * @brief Get field s16 from test_types message - * - * @return int16_t - */ -static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 27); -} - -/** - * @brief Get field s32 from test_types message - * - * @return int32_t - */ -static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 29); -} - -/** - * @brief Get field s64 from test_types message - * - * @return int64_t - */ -static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int64_t(msg, 33); -} - -/** - * @brief Get field f from test_types message - * - * @return float - */ -static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 41); -} - -/** - * @brief Get field d from test_types message - * - * @return double - */ -static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg) -{ - return _MAV_RETURN_double(msg, 45); -} - -/** - * @brief Get field u8_array from test_types message - * - * @return uint8_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array) -{ - return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 53); -} - -/** - * @brief Get field u16_array from test_types message - * - * @return uint16_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array) -{ - return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 56); -} - -/** - * @brief Get field u32_array from test_types message - * - * @return uint32_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array) -{ - return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 62); -} - -/** - * @brief Get field u64_array from test_types message - * - * @return uint64_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array) -{ - return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 74); -} - -/** - * @brief Get field s8_array from test_types message - * - * @return int8_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array) -{ - return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 98); -} - -/** - * @brief Get field s16_array from test_types message - * - * @return int16_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array) -{ - return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 101); -} - -/** - * @brief Get field s32_array from test_types message - * - * @return int32_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array) -{ - return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 107); -} - -/** - * @brief Get field s64_array from test_types message - * - * @return int64_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array) -{ - return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 119); -} - -/** - * @brief Get field f_array from test_types message - * - * @return float_array - */ -static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array) -{ - return _MAV_RETURN_float_array(msg, f_array, 3, 143); -} - -/** - * @brief Get field d_array from test_types message - * - * @return double_array - */ -static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array) -{ - return _MAV_RETURN_double_array(msg, d_array, 3, 155); -} - -/** - * @brief Decode a test_types message into a struct - * - * @param msg The message to decode - * @param test_types C-struct to decode the message contents into - */ -static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types) -{ -#if MAVLINK_NEED_BYTE_SWAP - test_types->c = mavlink_msg_test_types_get_c(msg); - mavlink_msg_test_types_get_s(msg, test_types->s); - test_types->u8 = mavlink_msg_test_types_get_u8(msg); - test_types->u16 = mavlink_msg_test_types_get_u16(msg); - test_types->u32 = mavlink_msg_test_types_get_u32(msg); - test_types->u64 = mavlink_msg_test_types_get_u64(msg); - test_types->s8 = mavlink_msg_test_types_get_s8(msg); - test_types->s16 = mavlink_msg_test_types_get_s16(msg); - test_types->s32 = mavlink_msg_test_types_get_s32(msg); - test_types->s64 = mavlink_msg_test_types_get_s64(msg); - test_types->f = mavlink_msg_test_types_get_f(msg); - test_types->d = mavlink_msg_test_types_get_d(msg); - mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array); - mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array); - mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array); - mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array); - mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array); - mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array); - mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array); - mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array); - mavlink_msg_test_types_get_f_array(msg, test_types->f_array); - mavlink_msg_test_types_get_d_array(msg, test_types->d_array); -#else - memcpy(test_types, _MAV_PAYLOAD(msg), 179); -#endif -} diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h deleted file mode 100644 index 23ee65986..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/test.h +++ /dev/null @@ -1,53 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from test.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef TEST_H -#define TEST_H - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {91, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} -#endif - -#ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_TEST - - - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -// ENUM DEFINITIONS - - - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_test_types.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // TEST_H diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h deleted file mode 100644 index 9b0fc041b..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v0.9/test/testsuite.h +++ /dev/null @@ -1,120 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from test.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef TEST_TESTSUITE_H -#define TEST_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL - -static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - - mavlink_test_test(system_id, component_id, last_msg); -} -#endif - - - - -static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_test_types_t packet_in = { - 'A', - "BCDEFGHIJ", - 230, - 17859, - 963498192, - 93372036854776941ULL, - 211, - 18639, - 963498972, - 93372036854777886LL, - 304.0, - 438.0, - { 228, 229, 230 }, - { 20147, 20148, 20149 }, - { 963500688, 963500689, 963500690 }, - { 93372036854780469, 93372036854780470, 93372036854780471 }, - { 171, 172, 173 }, - { 22487, 22488, 22489 }, - { 963503028, 963503029, 963503030 }, - { 93372036854783304, 93372036854783305, 93372036854783306 }, - { 1018.0, 1019.0, 1020.0 }, - { 1208.0, 1209.0, 1210.0 }, - }; - mavlink_test_types_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.c = packet_in.c; - packet1.u8 = packet_in.u8; - packet1.u16 = packet_in.u16; - packet1.u32 = packet_in.u32; - packet1.u64 = packet_in.u64; - packet1.s8 = packet_in.s8; - packet1.s16 = packet_in.s16; - packet1.s32 = packet_in.s32; - packet1.s64 = packet_in.s64; - packet1.f = packet_in.f; - packet1.d = packet_in.d; - - mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10); - mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3); - mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3); - mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3); - mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3); - mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3); - mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3); - mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3); - mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3); - mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3); - mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3); - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_test_types_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); - mavlink_msg_test_types_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); - mavlink_msg_test_types_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; i>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4); -} - -/** - * @brief Initiliaze the buffer for the X.25 CRC - * - * @param crcAccum the 16 bit X.25 CRC - */ -static inline void crc_init(uint16_t* crcAccum) -{ - *crcAccum = X25_INIT_CRC; -} - - -/** - * @brief Calculates the X.25 checksum on a byte buffer - * - * @param pBuffer buffer containing the byte array to hash - * @param length length of the byte array - * @return the checksum over the buffer bytes - **/ -static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length) -{ - uint16_t crcTmp; - crc_init(&crcTmp); - while (length--) { - crc_accumulate(*pBuffer++, &crcTmp); - } - return crcTmp; -} - -/** - * @brief Accumulate the X.25 CRC by adding an array of bytes - * - * The checksum function adds the hash of one char at a time to the - * 16 bit checksum (uint16_t). - * - * @param data new bytes to hash - * @param crcAccum the already accumulated checksum - **/ -static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length) -{ - const uint8_t *p = (const uint8_t *)pBuffer; - while (length--) { - crc_accumulate(*p++, crcAccum); - } -} - - - - -#endif /* _CHECKSUM_H_ */ - -#ifdef __cplusplus -} -#endif diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h deleted file mode 100644 index 39d6930e5..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_helpers.h +++ /dev/null @@ -1,507 +0,0 @@ -#ifndef _MAVLINK_HELPERS_H_ -#define _MAVLINK_HELPERS_H_ - -#include "string.h" -#include "checksum.h" -#include "mavlink_types.h" - -#ifndef MAVLINK_HELPER -#define MAVLINK_HELPER -#endif - -/* - internal function to give access to the channel status for each channel - */ -MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan) -{ - static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS]; - return &m_mavlink_status[chan]; -} - -/* - internal function to give access to the channel buffer for each channel - */ -MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan) -{ - -#if MAVLINK_EXTERNAL_RX_BUFFER - // No m_mavlink_message array defined in function, - // has to be defined externally -#ifndef m_mavlink_message -#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];) -#endif -#else - static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS]; -#endif - return &m_mavlink_buffer[chan]; -} - -/** - * @brief Finalize a MAVLink message with channel assignment - * - * This function calculates the checksum and sets length and aircraft id correctly. - * It assumes that the message id and the payload are already correctly set. This function - * can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack - * instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead. - * - * @param msg Message to finalize - * @param system_id Id of the sending (this) system, 1-127 - * @param length Message length - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length) -#endif -{ - // This code part is the same for all messages; - uint16_t checksum; - msg->magic = MAVLINK_STX; - msg->len = length; - msg->sysid = system_id; - msg->compid = component_id; - // One sequence number per component - msg->seq = mavlink_get_channel_status(chan)->current_tx_seq; - mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1; - checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); -#endif - mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF); - mavlink_ck_b(msg) = (uint8_t)(checksum >> 8); - - return length + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - - -/** - * @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length, uint8_t crc_extra) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra); -} -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length) -{ - return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length); -} -#endif - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); - -/** - * @brief Finalize a MAVLink message with channel assignment and send - */ -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, - uint8_t length, uint8_t crc_extra) -#else -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length) -#endif -{ - uint16_t checksum; - uint8_t buf[MAVLINK_NUM_HEADER_BYTES]; - uint8_t ck[2]; - mavlink_status_t *status = mavlink_get_channel_status(chan); - buf[0] = MAVLINK_STX; - buf[1] = length; - buf[2] = status->current_tx_seq; - buf[3] = mavlink_system.sysid; - buf[4] = mavlink_system.compid; - buf[5] = msgid; - status->current_tx_seq++; - checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN); - crc_accumulate_buffer(&checksum, packet, length); -#if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); -#endif - ck[0] = (uint8_t)(checksum & 0xFF); - ck[1] = (uint8_t)(checksum >> 8); - - MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); - _mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES); - _mavlink_send_uart(chan, packet, length); - _mavlink_send_uart(chan, (const char *)ck, 2); - MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length); -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -/** - * @brief Pack a message to send it over a serial byte stream - */ -MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg) -{ - memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len); - return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len; -} - -union __mavlink_bitfield { - uint8_t uint8; - int8_t int8; - uint16_t uint16; - int16_t int16; - uint32_t uint32; - int32_t int32; -}; - - -MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg) -{ - crc_init(&msg->checksum); -} - -MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c) -{ - crc_accumulate(c, &msg->checksum); -} - -/** - * This is a convenience function which handles the complete MAVLink parsing. - * the function will parse one byte at a time and return the complete packet once - * it could be successfully decoded. Checksum and other failures will be silently - * ignored. - * - * @param chan ID of the current channel. This allows to parse different channels with this function. - * a channel is not a physical message channel like a serial port, but a logic partition of - * the communication streams in this case. COMM_NB is the limit for the number of channels - * on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows - * @param c The char to barse - * - * @param returnMsg NULL if no message could be decoded, the message data else - * @return 0 if no message could be decoded, 1 else - * - * A typical use scenario of this function call is: - * - * @code - * #include // For fixed-width uint8_t type - * - * mavlink_message_t msg; - * int chan = 0; - * - * - * while(serial.bytesAvailable > 0) - * { - * uint8_t byte = serial.getNextByte(); - * if (mavlink_parse_char(chan, byte, &msg)) - * { - * printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid); - * } - * } - * - * - * @endcode - */ -MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status) -{ - /* - default message crc function. You can override this per-system to - put this data in a different memory segment - */ -#if MAVLINK_CRC_EXTRA -#ifndef MAVLINK_MESSAGE_CRC - static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; -#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid] -#endif -#endif - - mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message - mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status - int bufferIndex = 0; - - status->msg_received = 0; - - switch (status->parse_state) - { - case MAVLINK_PARSE_STATE_UNINIT: - case MAVLINK_PARSE_STATE_IDLE: - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - rxmsg->magic = c; - mavlink_start_checksum(rxmsg); - } - break; - - case MAVLINK_PARSE_STATE_GOT_STX: - if (status->msg_received -/* Support shorter buffers than the - default maximum packet size */ -#if (MAVLINK_MAX_PAYLOAD_LEN < 255) - || c > MAVLINK_MAX_PAYLOAD_LEN -#endif - ) - { - status->buffer_overrun++; - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - } - else - { - // NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2 - rxmsg->len = c; - status->packet_idx = 0; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH; - } - break; - - case MAVLINK_PARSE_STATE_GOT_LENGTH: - rxmsg->seq = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ; - break; - - case MAVLINK_PARSE_STATE_GOT_SEQ: - rxmsg->sysid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID; - break; - - case MAVLINK_PARSE_STATE_GOT_SYSID: - rxmsg->compid = c; - mavlink_update_checksum(rxmsg, c); - status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID; - break; - - case MAVLINK_PARSE_STATE_GOT_COMPID: - rxmsg->msgid = c; - mavlink_update_checksum(rxmsg, c); - if (rxmsg->len == 0) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID; - } - break; - - case MAVLINK_PARSE_STATE_GOT_MSGID: - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c; - mavlink_update_checksum(rxmsg, c); - if (status->packet_idx == rxmsg->len) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD; - } - break; - - case MAVLINK_PARSE_STATE_GOT_PAYLOAD: -#if MAVLINK_CRC_EXTRA - mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid)); -#endif - if (c != (rxmsg->checksum & 0xFF)) { - // Check first checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - } - else - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1; - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c; - } - break; - - case MAVLINK_PARSE_STATE_GOT_CRC1: - if (c != (rxmsg->checksum >> 8)) { - // Check second checksum byte - status->parse_error++; - status->msg_received = 0; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - if (c == MAVLINK_STX) - { - status->parse_state = MAVLINK_PARSE_STATE_GOT_STX; - rxmsg->len = 0; - mavlink_start_checksum(rxmsg); - } - } - else - { - // Successfully got message - status->msg_received = 1; - status->parse_state = MAVLINK_PARSE_STATE_IDLE; - _MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c; - memcpy(r_message, rxmsg, sizeof(mavlink_message_t)); - } - break; - } - - bufferIndex++; - // If a message has been sucessfully decoded, check index - if (status->msg_received == 1) - { - //while(status->current_seq != rxmsg->seq) - //{ - // status->packet_rx_drop_count++; - // status->current_seq++; - //} - status->current_rx_seq = rxmsg->seq; - // Initial condition: If no packet has been received so far, drop count is undefined - if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0; - // Count this packet as received - status->packet_rx_success_count++; - } - - r_mavlink_status->current_rx_seq = status->current_rx_seq+1; - r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count; - r_mavlink_status->packet_rx_drop_count = status->parse_error; - status->parse_error = 0; - return status->msg_received; -} - -/** - * @brief Put a bitfield of length 1-32 bit into the buffer - * - * @param b the value to add, will be encoded in the bitfield - * @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc. - * @param packet_index the position in the packet (the index of the first byte to use) - * @param bit_index the position in the byte (the index of the first bit to use) - * @param buffer packet buffer to write into - * @return new position of the last used byte in the buffer - */ -MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer) -{ - uint16_t bits_remain = bits; - // Transform number into network order - int32_t v; - uint8_t i_bit_index, i_byte_index, curr_bits_n; -#if MAVLINK_NEED_BYTE_SWAP - union { - int32_t i; - uint8_t b[4]; - } bin, bout; - bin.i = b; - bout.b[0] = bin.b[3]; - bout.b[1] = bin.b[2]; - bout.b[2] = bin.b[1]; - bout.b[3] = bin.b[0]; - v = bout.i; -#else - v = b; -#endif - - // buffer in - // 01100000 01000000 00000000 11110001 - // buffer out - // 11110001 00000000 01000000 01100000 - - // Existing partly filled byte (four free slots) - // 0111xxxx - - // Mask n free bits - // 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1 - // = ((uint32_t)(1 << n)) - 1; // = 2^n - 1 - - // Shift n bits into the right position - // out = in >> n; - - // Mask and shift bytes - i_bit_index = bit_index; - i_byte_index = packet_index; - if (bit_index > 0) - { - // If bits were available at start, they were available - // in the byte before the current index - i_byte_index--; - } - - // While bits have not been packed yet - while (bits_remain > 0) - { - // Bits still have to be packed - // there can be more than 8 bits, so - // we might have to pack them into more than one byte - - // First pack everything we can into the current 'open' byte - //curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8 - //FIXME - if (bits_remain <= (uint8_t)(8 - i_bit_index)) - { - // Enough space - curr_bits_n = (uint8_t)bits_remain; - } - else - { - curr_bits_n = (8 - i_bit_index); - } - - // Pack these n bits into the current byte - // Mask out whatever was at that position with ones (xxx11111) - buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n)); - // Put content to this position, by masking out the non-used part - buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v); - - // Increment the bit index - i_bit_index += curr_bits_n; - - // Now proceed to the next byte, if necessary - bits_remain -= curr_bits_n; - if (bits_remain > 0) - { - // Offer another 8 bits / one byte - i_byte_index++; - i_bit_index = 0; - } - } - - *r_bit_index = i_bit_index; - // If a partly filled byte is present, mark this as consumed - if (i_bit_index != 7) i_byte_index++; - return i_byte_index - packet_index; -} - -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -// To make MAVLink work on your MCU, define comm_send_ch() if you wish -// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a -// whole packet at a time - -/* - -#include "mavlink_types.h" - -void comm_send_ch(mavlink_channel_t chan, uint8_t ch) -{ - if (chan == MAVLINK_COMM_0) - { - uart0_transmit(ch); - } - if (chan == MAVLINK_COMM_1) - { - uart1_transmit(ch); - } -} - */ - -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len) -{ -#ifdef MAVLINK_SEND_UART_BYTES - /* this is the more efficient approach, if the platform - defines it */ - MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len); -#else - /* fallback to one byte at a time */ - uint16_t i; - for (i = 0; i < len; i++) { - comm_send_ch(chan, (uint8_t)buf[i]); - } -#endif -} -#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS - -#endif /* _MAVLINK_HELPERS_H_ */ diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp deleted file mode 100644 index fd3ddd026..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_protobuf_manager.hpp +++ /dev/null @@ -1,377 +0,0 @@ -#ifndef MAVLINKPROTOBUFMANAGER_HPP -#define MAVLINKPROTOBUFMANAGER_HPP - -#include -#include -#include -#include - -#include -#include -#include -#include - -namespace mavlink -{ - -class ProtobufManager -{ -public: - ProtobufManager() - : mRegisteredTypeCount(0) - , mStreamID(0) - , mVerbose(false) - , kExtendedHeaderSize(MAVLINK_EXTENDED_HEADER_LEN) - , kExtendedPayloadMaxSize(MAVLINK_MAX_EXTENDED_PAYLOAD_LEN) - { - // register GLOverlay - { - std::tr1::shared_ptr msg(new px::GLOverlay); - registerType(msg); - } - - // register ObstacleList - { - std::tr1::shared_ptr msg(new px::ObstacleList); - registerType(msg); - } - - // register ObstacleMap - { - std::tr1::shared_ptr msg(new px::ObstacleMap); - registerType(msg); - } - - // register Path - { - std::tr1::shared_ptr msg(new px::Path); - registerType(msg); - } - - // register PointCloudXYZI - { - std::tr1::shared_ptr msg(new px::PointCloudXYZI); - registerType(msg); - } - - // register PointCloudXYZRGB - { - std::tr1::shared_ptr msg(new px::PointCloudXYZRGB); - registerType(msg); - } - - // register RGBDImage - { - std::tr1::shared_ptr msg(new px::RGBDImage); - registerType(msg); - } - - srand(time(NULL)); - mStreamID = rand() + 1; - } - - bool fragmentMessage(uint8_t system_id, uint8_t component_id, - uint8_t target_system, uint8_t target_component, - const google::protobuf::Message& protobuf_msg, - std::vector& fragments) const - { - TypeMap::const_iterator it = mTypeMap.find(protobuf_msg.GetTypeName()); - if (it == mTypeMap.end()) - { - std::cout << "# WARNING: Protobuf message with type " - << protobuf_msg.GetTypeName() << " is not registered." - << std::endl; - return false; - } - - uint8_t typecode = it->second; - - std::string data = protobuf_msg.SerializeAsString(); - - int fragmentCount = (protobuf_msg.ByteSize() + kExtendedPayloadMaxSize - 1) / kExtendedPayloadMaxSize; - unsigned int offset = 0; - - for (int i = 0; i < fragmentCount; ++i) - { - mavlink_extended_message_t fragment; - - // write extended header data - uint8_t* payload = reinterpret_cast(fragment.base_msg.payload64); - unsigned int length = 0; - uint8_t flags = 0; - - if (i < fragmentCount - 1) - { - length = kExtendedPayloadMaxSize; - flags |= 0x1; - } - else - { - length = protobuf_msg.ByteSize() - kExtendedPayloadMaxSize * (fragmentCount - 1); - } - - memcpy(payload, &target_system, 1); - memcpy(payload + 1, &target_component, 1); - memcpy(payload + 2, &typecode, 1); - memcpy(payload + 3, &length, 4); - memcpy(payload + 7, &mStreamID, 2); - memcpy(payload + 9, &offset, 4); - memcpy(payload + 13, &flags, 1); - - fragment.base_msg.msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE; - mavlink_finalize_message(&fragment.base_msg, system_id, component_id, kExtendedHeaderSize, 0); - - // write extended payload data - fragment.extended_payload_len = length; - memcpy(fragment.extended_payload, &data[offset], length); - - fragments.push_back(fragment); - offset += length; - } - - if (mVerbose) - { - std::cerr << "# INFO: Split extended message with size " - << protobuf_msg.ByteSize() << " into " - << fragmentCount << " fragments." << std::endl; - } - - return true; - } - - bool cacheFragment(mavlink_extended_message_t& msg) - { - if (!validFragment(msg)) - { - if (mVerbose) - { - std::cerr << "# WARNING: Message is not a valid fragment. " - << "Dropping message..." << std::endl; - } - return false; - } - - // read extended header - uint8_t* payload = reinterpret_cast(msg.base_msg.payload64); - uint8_t typecode = 0; - unsigned int length = 0; - unsigned short streamID = 0; - unsigned int offset = 0; - uint8_t flags = 0; - - memcpy(&typecode, payload + 2, 1); - memcpy(&length, payload + 3, 4); - memcpy(&streamID, payload + 7, 2); - memcpy(&offset, payload + 9, 4); - memcpy(&flags, payload + 13, 1); - - if (typecode >= mTypeMap.size()) - { - std::cout << "# WARNING: Protobuf message with type code " - << static_cast(typecode) << " is not registered." << std::endl; - return false; - } - - bool reassemble = false; - - FragmentQueue::iterator it = mFragmentQueue.find(streamID); - if (it == mFragmentQueue.end()) - { - if (offset == 0) - { - mFragmentQueue[streamID].push_back(msg); - - if ((flags & 0x1) != 0x1) - { - reassemble = true; - } - - if (mVerbose) - { - std::cerr << "# INFO: Added fragment to new queue." - << std::endl; - } - } - else - { - if (mVerbose) - { - std::cerr << "# WARNING: Message is not a valid fragment. " - << "Dropping message..." << std::endl; - } - } - } - else - { - std::deque& queue = it->second; - - if (queue.empty()) - { - if (offset == 0) - { - queue.push_back(msg); - - if ((flags & 0x1) != 0x1) - { - reassemble = true; - } - } - else - { - if (mVerbose) - { - std::cerr << "# WARNING: Message is not a valid fragment. " - << "Dropping message..." << std::endl; - } - } - } - else - { - if (fragmentDataSize(queue.back()) + fragmentOffset(queue.back()) != offset) - { - if (mVerbose) - { - std::cerr << "# WARNING: Previous fragment(s) have been lost. " - << "Dropping message and clearing queue..." << std::endl; - } - queue.clear(); - } - else - { - queue.push_back(msg); - - if ((flags & 0x1) != 0x1) - { - reassemble = true; - } - } - } - } - - if (reassemble) - { - std::deque& queue = mFragmentQueue[streamID]; - - std::string data; - for (size_t i = 0; i < queue.size(); ++i) - { - mavlink_extended_message_t& mavlink_msg = queue.at(i); - - data.append(reinterpret_cast(&mavlink_msg.extended_payload[0]), - static_cast(mavlink_msg.extended_payload_len)); - } - - mMessages.at(typecode)->ParseFromString(data); - - mMessageAvailable.at(typecode) = true; - - queue.clear(); - - if (mVerbose) - { - std::cerr << "# INFO: Reassembled fragments for message with typename " - << mMessages.at(typecode)->GetTypeName() << " and size " - << mMessages.at(typecode)->ByteSize() - << "." << std::endl; - } - } - - return true; - } - - bool getMessage(std::tr1::shared_ptr& msg) - { - for (size_t i = 0; i < mMessageAvailable.size(); ++i) - { - if (mMessageAvailable.at(i)) - { - msg = mMessages.at(i); - mMessageAvailable.at(i) = false; - - return true; - } - } - - return false; - } - -private: - void registerType(const std::tr1::shared_ptr& msg) - { - mTypeMap[msg->GetTypeName()] = mRegisteredTypeCount; - ++mRegisteredTypeCount; - mMessages.push_back(msg); - mMessageAvailable.push_back(false); - } - - bool validFragment(const mavlink_extended_message_t& msg) const - { - if (msg.base_msg.magic != MAVLINK_STX || - msg.base_msg.len != kExtendedHeaderSize || - msg.base_msg.msgid != MAVLINK_MSG_ID_EXTENDED_MESSAGE) - { - return false; - } - - uint16_t checksum; - checksum = crc_calculate(reinterpret_cast(&msg.base_msg.len), MAVLINK_CORE_HEADER_LEN); - crc_accumulate_buffer(&checksum, reinterpret_cast(&msg.base_msg.payload64), kExtendedHeaderSize); -#if MAVLINK_CRC_EXTRA - static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; - crc_accumulate(mavlink_message_crcs[msg.base_msg.msgid], &checksum); -#endif - - if (mavlink_ck_a(&(msg.base_msg)) != (uint8_t)(checksum & 0xFF) && - mavlink_ck_b(&(msg.base_msg)) != (uint8_t)(checksum >> 8)) - { - return false; - } - - return true; - } - - unsigned int fragmentDataSize(const mavlink_extended_message_t& msg) const - { - const uint8_t* payload = reinterpret_cast(msg.base_msg.payload64); - - return *(reinterpret_cast(payload + 3)); - } - - unsigned int fragmentOffset(const mavlink_extended_message_t& msg) const - { - const uint8_t* payload = reinterpret_cast(msg.base_msg.payload64); - - return *(reinterpret_cast(payload + 9)); - } - - int mRegisteredTypeCount; - unsigned short mStreamID; - bool mVerbose; - - typedef std::map TypeMap; - TypeMap mTypeMap; - std::vector< std::tr1::shared_ptr > mMessages; - std::vector mMessageAvailable; - - typedef std::map > FragmentQueue; - FragmentQueue mFragmentQueue; - - const int kExtendedHeaderSize; - /** - * Extended header structure - * ========================= - * byte 0 - target_system - * byte 1 - target_component - * byte 2 - extended message id (type code) - * bytes 3-6 - extended payload size in bytes - * byte 7-8 - stream ID - * byte 9-12 - fragment offset - * byte 13 - fragment flags (bit 0 - 1=more fragments, 0=last fragment) - */ - - const int kExtendedPayloadMaxSize; -}; - -} - -#endif diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h deleted file mode 100644 index 5fbde97f7..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/mavlink_types.h +++ /dev/null @@ -1,158 +0,0 @@ -#ifndef MAVLINK_TYPES_H_ -#define MAVLINK_TYPES_H_ - -#include - -#ifndef MAVLINK_MAX_PAYLOAD_LEN -// it is possible to override this, but be careful! -#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length -#endif - -#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte) -#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum -#define MAVLINK_NUM_CHECKSUM_BYTES 2 -#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES) - -#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length - -#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255 -#define MAVLINK_EXTENDED_HEADER_LEN 14 - -#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__) - /* full fledged 32bit++ OS */ - #define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507 -#else - /* small microcontrollers */ - #define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048 -#endif - -#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES) - -typedef struct param_union { - union { - float param_float; - int32_t param_int32; - uint32_t param_uint32; - uint8_t param_uint8; - uint8_t bytes[4]; - }; - uint8_t type; -} mavlink_param_union_t; - -typedef struct __mavlink_system { - uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function - uint8_t type; ///< Unused, can be used by user to store the system's type - uint8_t state; ///< Unused, can be used by user to store the system's state - uint8_t mode; ///< Unused, can be used by user to store the system's mode - uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode -} mavlink_system_t; - -typedef struct __mavlink_message { - uint16_t checksum; /// sent at end of packet - uint8_t magic; ///< protocol magic marker - uint8_t len; ///< Length of payload - uint8_t seq; ///< Sequence of packet - uint8_t sysid; ///< ID of message sender system/aircraft - uint8_t compid; ///< ID of the message sender component - uint8_t msgid; ///< ID of message in payload - uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8]; -} mavlink_message_t; - - -typedef struct __mavlink_extended_message { - mavlink_message_t base_msg; - int32_t extended_payload_len; ///< Length of extended payload if any - uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN]; -} mavlink_extended_message_t; - - -typedef enum { - MAVLINK_TYPE_CHAR = 0, - MAVLINK_TYPE_UINT8_T = 1, - MAVLINK_TYPE_INT8_T = 2, - MAVLINK_TYPE_UINT16_T = 3, - MAVLINK_TYPE_INT16_T = 4, - MAVLINK_TYPE_UINT32_T = 5, - MAVLINK_TYPE_INT32_T = 6, - MAVLINK_TYPE_UINT64_T = 7, - MAVLINK_TYPE_INT64_T = 8, - MAVLINK_TYPE_FLOAT = 9, - MAVLINK_TYPE_DOUBLE = 10 -} mavlink_message_type_t; - -#define MAVLINK_MAX_FIELDS 64 - -typedef struct __mavlink_field_info { - const char *name; // name of this field - const char *print_format; // printing format hint, or NULL - mavlink_message_type_t type; // type of this field - unsigned int array_length; // if non-zero, field is an array - unsigned int wire_offset; // offset of each field in the payload - unsigned int structure_offset; // offset in a C structure -} mavlink_field_info_t; - -// note that in this structure the order of fields is the order -// in the XML file, not necessary the wire order -typedef struct __mavlink_message_info { - const char *name; // name of the message - unsigned num_fields; // how many fields in this message - mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information -} mavlink_message_info_t; - -#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0]))) -#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0]))) - -// checksum is immediately after the payload bytes -#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) -#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg)) - -typedef enum { - MAVLINK_COMM_0, - MAVLINK_COMM_1, - MAVLINK_COMM_2, - MAVLINK_COMM_3 -} mavlink_channel_t; - -/* - * applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number - * of buffers they will use. If more are used, then the result will be - * a stack overrun - */ -#ifndef MAVLINK_COMM_NUM_BUFFERS -#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32) -# define MAVLINK_COMM_NUM_BUFFERS 16 -#else -# define MAVLINK_COMM_NUM_BUFFERS 4 -#endif -#endif - -typedef enum { - MAVLINK_PARSE_STATE_UNINIT=0, - MAVLINK_PARSE_STATE_IDLE, - MAVLINK_PARSE_STATE_GOT_STX, - MAVLINK_PARSE_STATE_GOT_SEQ, - MAVLINK_PARSE_STATE_GOT_LENGTH, - MAVLINK_PARSE_STATE_GOT_SYSID, - MAVLINK_PARSE_STATE_GOT_COMPID, - MAVLINK_PARSE_STATE_GOT_MSGID, - MAVLINK_PARSE_STATE_GOT_PAYLOAD, - MAVLINK_PARSE_STATE_GOT_CRC1 -} mavlink_parse_state_t; ///< The state machine for the comm parser - -typedef struct __mavlink_status { - uint8_t msg_received; ///< Number of received messages - uint8_t buffer_overrun; ///< Number of buffer overruns - uint8_t parse_error; ///< Number of parse errors - mavlink_parse_state_t parse_state; ///< Parsing state machine - uint8_t packet_idx; ///< Index in current packet - uint8_t current_rx_seq; ///< Sequence number of last packet received - uint8_t current_tx_seq; ///< Sequence number of last packet sent - uint16_t packet_rx_success_count; ///< Received packets - uint16_t packet_rx_drop_count; ///< Number of packet drops -} mavlink_status_t; - -#define MAVLINK_BIG_ENDIAN 0 -#define MAVLINK_LITTLE_ENDIAN 1 - -#endif /* MAVLINK_TYPES_H_ */ diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h deleted file mode 100644 index 7556606e9..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/pixhawk/pixhawk.pb.h +++ /dev/null @@ -1,3663 +0,0 @@ -// Generated by the protocol buffer compiler. DO NOT EDIT! -// source: pixhawk.proto - -#ifndef PROTOBUF_pixhawk_2eproto__INCLUDED -#define PROTOBUF_pixhawk_2eproto__INCLUDED - -#include - -#include - -#if GOOGLE_PROTOBUF_VERSION < 2004000 -#error This file was generated by a newer version of protoc which is -#error incompatible with your Protocol Buffer headers. Please update -#error your headers. -#endif -#if 2004001 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION -#error This file was generated by an older version of protoc which is -#error incompatible with your Protocol Buffer headers. Please -#error regenerate this file with a newer version of protoc. -#endif - -#include -#include -#include -#include -// @@protoc_insertion_point(includes) - -namespace px { - -// Internal implementation detail -- do not call these. -void protobuf_AddDesc_pixhawk_2eproto(); -void protobuf_AssignDesc_pixhawk_2eproto(); -void protobuf_ShutdownFile_pixhawk_2eproto(); - -class HeaderInfo; -class GLOverlay; -class Obstacle; -class ObstacleList; -class ObstacleMap; -class Path; -class PointCloudXYZI; -class PointCloudXYZI_PointXYZI; -class PointCloudXYZRGB; -class PointCloudXYZRGB_PointXYZRGB; -class RGBDImage; -class Waypoint; - -enum GLOverlay_CoordinateFrameType { - GLOverlay_CoordinateFrameType_GLOBAL = 0, - GLOverlay_CoordinateFrameType_LOCAL = 1 -}; -bool GLOverlay_CoordinateFrameType_IsValid(int value); -const GLOverlay_CoordinateFrameType GLOverlay_CoordinateFrameType_CoordinateFrameType_MIN = GLOverlay_CoordinateFrameType_GLOBAL; -const GLOverlay_CoordinateFrameType GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX = GLOverlay_CoordinateFrameType_LOCAL; -const int GLOverlay_CoordinateFrameType_CoordinateFrameType_ARRAYSIZE = GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX + 1; - -const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor(); -inline const ::std::string& GLOverlay_CoordinateFrameType_Name(GLOverlay_CoordinateFrameType value) { - return ::google::protobuf::internal::NameOfEnum( - GLOverlay_CoordinateFrameType_descriptor(), value); -} -inline bool GLOverlay_CoordinateFrameType_Parse( - const ::std::string& name, GLOverlay_CoordinateFrameType* value) { - return ::google::protobuf::internal::ParseNamedEnum( - GLOverlay_CoordinateFrameType_descriptor(), name, value); -} -enum GLOverlay_Mode { - GLOverlay_Mode_POINTS = 0, - GLOverlay_Mode_LINES = 1, - GLOverlay_Mode_LINE_STRIP = 2, - GLOverlay_Mode_LINE_LOOP = 3, - GLOverlay_Mode_TRIANGLES = 4, - GLOverlay_Mode_TRIANGLE_STRIP = 5, - GLOverlay_Mode_TRIANGLE_FAN = 6, - GLOverlay_Mode_QUADS = 7, - GLOverlay_Mode_QUAD_STRIP = 8, - GLOverlay_Mode_POLYGON = 9, - GLOverlay_Mode_SOLID_CIRCLE = 10, - GLOverlay_Mode_WIRE_CIRCLE = 11, - GLOverlay_Mode_SOLID_CUBE = 12, - GLOverlay_Mode_WIRE_CUBE = 13 -}; -bool GLOverlay_Mode_IsValid(int value); -const GLOverlay_Mode GLOverlay_Mode_Mode_MIN = GLOverlay_Mode_POINTS; -const GLOverlay_Mode GLOverlay_Mode_Mode_MAX = GLOverlay_Mode_WIRE_CUBE; -const int GLOverlay_Mode_Mode_ARRAYSIZE = GLOverlay_Mode_Mode_MAX + 1; - -const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor(); -inline const ::std::string& GLOverlay_Mode_Name(GLOverlay_Mode value) { - return ::google::protobuf::internal::NameOfEnum( - GLOverlay_Mode_descriptor(), value); -} -inline bool GLOverlay_Mode_Parse( - const ::std::string& name, GLOverlay_Mode* value) { - return ::google::protobuf::internal::ParseNamedEnum( - GLOverlay_Mode_descriptor(), name, value); -} -enum GLOverlay_Identifier { - GLOverlay_Identifier_END = 14, - GLOverlay_Identifier_VERTEX2F = 15, - GLOverlay_Identifier_VERTEX3F = 16, - GLOverlay_Identifier_ROTATEF = 17, - GLOverlay_Identifier_TRANSLATEF = 18, - GLOverlay_Identifier_SCALEF = 19, - GLOverlay_Identifier_PUSH_MATRIX = 20, - GLOverlay_Identifier_POP_MATRIX = 21, - GLOverlay_Identifier_COLOR3F = 22, - GLOverlay_Identifier_COLOR4F = 23, - GLOverlay_Identifier_POINTSIZE = 24, - GLOverlay_Identifier_LINEWIDTH = 25 -}; -bool GLOverlay_Identifier_IsValid(int value); -const GLOverlay_Identifier GLOverlay_Identifier_Identifier_MIN = GLOverlay_Identifier_END; -const GLOverlay_Identifier GLOverlay_Identifier_Identifier_MAX = GLOverlay_Identifier_LINEWIDTH; -const int GLOverlay_Identifier_Identifier_ARRAYSIZE = GLOverlay_Identifier_Identifier_MAX + 1; - -const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor(); -inline const ::std::string& GLOverlay_Identifier_Name(GLOverlay_Identifier value) { - return ::google::protobuf::internal::NameOfEnum( - GLOverlay_Identifier_descriptor(), value); -} -inline bool GLOverlay_Identifier_Parse( - const ::std::string& name, GLOverlay_Identifier* value) { - return ::google::protobuf::internal::ParseNamedEnum( - GLOverlay_Identifier_descriptor(), name, value); -} -// =================================================================== - -class HeaderInfo : public ::google::protobuf::Message { - public: - HeaderInfo(); - virtual ~HeaderInfo(); - - HeaderInfo(const HeaderInfo& from); - - inline HeaderInfo& operator=(const HeaderInfo& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const HeaderInfo& default_instance(); - - void Swap(HeaderInfo* other); - - // implements Message ---------------------------------------------- - - HeaderInfo* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const HeaderInfo& from); - void MergeFrom(const HeaderInfo& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required int32 source_sysid = 1; - inline bool has_source_sysid() const; - inline void clear_source_sysid(); - static const int kSourceSysidFieldNumber = 1; - inline ::google::protobuf::int32 source_sysid() const; - inline void set_source_sysid(::google::protobuf::int32 value); - - // required int32 source_compid = 2; - inline bool has_source_compid() const; - inline void clear_source_compid(); - static const int kSourceCompidFieldNumber = 2; - inline ::google::protobuf::int32 source_compid() const; - inline void set_source_compid(::google::protobuf::int32 value); - - // required double timestamp = 3; - inline bool has_timestamp() const; - inline void clear_timestamp(); - static const int kTimestampFieldNumber = 3; - inline double timestamp() const; - inline void set_timestamp(double value); - - // @@protoc_insertion_point(class_scope:px.HeaderInfo) - private: - inline void set_has_source_sysid(); - inline void clear_has_source_sysid(); - inline void set_has_source_compid(); - inline void clear_has_source_compid(); - inline void set_has_timestamp(); - inline void clear_has_timestamp(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::google::protobuf::int32 source_sysid_; - ::google::protobuf::int32 source_compid_; - double timestamp_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(3 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static HeaderInfo* default_instance_; -}; -// ------------------------------------------------------------------- - -class GLOverlay : public ::google::protobuf::Message { - public: - GLOverlay(); - virtual ~GLOverlay(); - - GLOverlay(const GLOverlay& from); - - inline GLOverlay& operator=(const GLOverlay& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const GLOverlay& default_instance(); - - void Swap(GLOverlay* other); - - // implements Message ---------------------------------------------- - - GLOverlay* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const GLOverlay& from); - void MergeFrom(const GLOverlay& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - typedef GLOverlay_CoordinateFrameType CoordinateFrameType; - static const CoordinateFrameType GLOBAL = GLOverlay_CoordinateFrameType_GLOBAL; - static const CoordinateFrameType LOCAL = GLOverlay_CoordinateFrameType_LOCAL; - static inline bool CoordinateFrameType_IsValid(int value) { - return GLOverlay_CoordinateFrameType_IsValid(value); - } - static const CoordinateFrameType CoordinateFrameType_MIN = - GLOverlay_CoordinateFrameType_CoordinateFrameType_MIN; - static const CoordinateFrameType CoordinateFrameType_MAX = - GLOverlay_CoordinateFrameType_CoordinateFrameType_MAX; - static const int CoordinateFrameType_ARRAYSIZE = - GLOverlay_CoordinateFrameType_CoordinateFrameType_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* - CoordinateFrameType_descriptor() { - return GLOverlay_CoordinateFrameType_descriptor(); - } - static inline const ::std::string& CoordinateFrameType_Name(CoordinateFrameType value) { - return GLOverlay_CoordinateFrameType_Name(value); - } - static inline bool CoordinateFrameType_Parse(const ::std::string& name, - CoordinateFrameType* value) { - return GLOverlay_CoordinateFrameType_Parse(name, value); - } - - typedef GLOverlay_Mode Mode; - static const Mode POINTS = GLOverlay_Mode_POINTS; - static const Mode LINES = GLOverlay_Mode_LINES; - static const Mode LINE_STRIP = GLOverlay_Mode_LINE_STRIP; - static const Mode LINE_LOOP = GLOverlay_Mode_LINE_LOOP; - static const Mode TRIANGLES = GLOverlay_Mode_TRIANGLES; - static const Mode TRIANGLE_STRIP = GLOverlay_Mode_TRIANGLE_STRIP; - static const Mode TRIANGLE_FAN = GLOverlay_Mode_TRIANGLE_FAN; - static const Mode QUADS = GLOverlay_Mode_QUADS; - static const Mode QUAD_STRIP = GLOverlay_Mode_QUAD_STRIP; - static const Mode POLYGON = GLOverlay_Mode_POLYGON; - static const Mode SOLID_CIRCLE = GLOverlay_Mode_SOLID_CIRCLE; - static const Mode WIRE_CIRCLE = GLOverlay_Mode_WIRE_CIRCLE; - static const Mode SOLID_CUBE = GLOverlay_Mode_SOLID_CUBE; - static const Mode WIRE_CUBE = GLOverlay_Mode_WIRE_CUBE; - static inline bool Mode_IsValid(int value) { - return GLOverlay_Mode_IsValid(value); - } - static const Mode Mode_MIN = - GLOverlay_Mode_Mode_MIN; - static const Mode Mode_MAX = - GLOverlay_Mode_Mode_MAX; - static const int Mode_ARRAYSIZE = - GLOverlay_Mode_Mode_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* - Mode_descriptor() { - return GLOverlay_Mode_descriptor(); - } - static inline const ::std::string& Mode_Name(Mode value) { - return GLOverlay_Mode_Name(value); - } - static inline bool Mode_Parse(const ::std::string& name, - Mode* value) { - return GLOverlay_Mode_Parse(name, value); - } - - typedef GLOverlay_Identifier Identifier; - static const Identifier END = GLOverlay_Identifier_END; - static const Identifier VERTEX2F = GLOverlay_Identifier_VERTEX2F; - static const Identifier VERTEX3F = GLOverlay_Identifier_VERTEX3F; - static const Identifier ROTATEF = GLOverlay_Identifier_ROTATEF; - static const Identifier TRANSLATEF = GLOverlay_Identifier_TRANSLATEF; - static const Identifier SCALEF = GLOverlay_Identifier_SCALEF; - static const Identifier PUSH_MATRIX = GLOverlay_Identifier_PUSH_MATRIX; - static const Identifier POP_MATRIX = GLOverlay_Identifier_POP_MATRIX; - static const Identifier COLOR3F = GLOverlay_Identifier_COLOR3F; - static const Identifier COLOR4F = GLOverlay_Identifier_COLOR4F; - static const Identifier POINTSIZE = GLOverlay_Identifier_POINTSIZE; - static const Identifier LINEWIDTH = GLOverlay_Identifier_LINEWIDTH; - static inline bool Identifier_IsValid(int value) { - return GLOverlay_Identifier_IsValid(value); - } - static const Identifier Identifier_MIN = - GLOverlay_Identifier_Identifier_MIN; - static const Identifier Identifier_MAX = - GLOverlay_Identifier_Identifier_MAX; - static const int Identifier_ARRAYSIZE = - GLOverlay_Identifier_Identifier_ARRAYSIZE; - static inline const ::google::protobuf::EnumDescriptor* - Identifier_descriptor() { - return GLOverlay_Identifier_descriptor(); - } - static inline const ::std::string& Identifier_Name(Identifier value) { - return GLOverlay_Identifier_Name(value); - } - static inline bool Identifier_Parse(const ::std::string& name, - Identifier* value) { - return GLOverlay_Identifier_Parse(name, value); - } - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // optional string name = 2; - inline bool has_name() const; - inline void clear_name(); - static const int kNameFieldNumber = 2; - inline const ::std::string& name() const; - inline void set_name(const ::std::string& value); - inline void set_name(const char* value); - inline void set_name(const char* value, size_t size); - inline ::std::string* mutable_name(); - inline ::std::string* release_name(); - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - inline bool has_coordinateframetype() const; - inline void clear_coordinateframetype(); - static const int kCoordinateFrameTypeFieldNumber = 3; - inline ::px::GLOverlay_CoordinateFrameType coordinateframetype() const; - inline void set_coordinateframetype(::px::GLOverlay_CoordinateFrameType value); - - // optional double origin_x = 4; - inline bool has_origin_x() const; - inline void clear_origin_x(); - static const int kOriginXFieldNumber = 4; - inline double origin_x() const; - inline void set_origin_x(double value); - - // optional double origin_y = 5; - inline bool has_origin_y() const; - inline void clear_origin_y(); - static const int kOriginYFieldNumber = 5; - inline double origin_y() const; - inline void set_origin_y(double value); - - // optional double origin_z = 6; - inline bool has_origin_z() const; - inline void clear_origin_z(); - static const int kOriginZFieldNumber = 6; - inline double origin_z() const; - inline void set_origin_z(double value); - - // optional bytes data = 7; - inline bool has_data() const; - inline void clear_data(); - static const int kDataFieldNumber = 7; - inline const ::std::string& data() const; - inline void set_data(const ::std::string& value); - inline void set_data(const char* value); - inline void set_data(const void* value, size_t size); - inline ::std::string* mutable_data(); - inline ::std::string* release_data(); - - // @@protoc_insertion_point(class_scope:px.GLOverlay) - private: - inline void set_has_header(); - inline void clear_has_header(); - inline void set_has_name(); - inline void clear_has_name(); - inline void set_has_coordinateframetype(); - inline void clear_has_coordinateframetype(); - inline void set_has_origin_x(); - inline void clear_has_origin_x(); - inline void set_has_origin_y(); - inline void clear_has_origin_y(); - inline void set_has_origin_z(); - inline void clear_has_origin_z(); - inline void set_has_data(); - inline void clear_has_data(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::std::string* name_; - double origin_x_; - double origin_y_; - double origin_z_; - ::std::string* data_; - int coordinateframetype_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(7 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static GLOverlay* default_instance_; -}; -// ------------------------------------------------------------------- - -class Obstacle : public ::google::protobuf::Message { - public: - Obstacle(); - virtual ~Obstacle(); - - Obstacle(const Obstacle& from); - - inline Obstacle& operator=(const Obstacle& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const Obstacle& default_instance(); - - void Swap(Obstacle* other); - - // implements Message ---------------------------------------------- - - Obstacle* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const Obstacle& from); - void MergeFrom(const Obstacle& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // optional float x = 1; - inline bool has_x() const; - inline void clear_x(); - static const int kXFieldNumber = 1; - inline float x() const; - inline void set_x(float value); - - // optional float y = 2; - inline bool has_y() const; - inline void clear_y(); - static const int kYFieldNumber = 2; - inline float y() const; - inline void set_y(float value); - - // optional float z = 3; - inline bool has_z() const; - inline void clear_z(); - static const int kZFieldNumber = 3; - inline float z() const; - inline void set_z(float value); - - // optional float length = 4; - inline bool has_length() const; - inline void clear_length(); - static const int kLengthFieldNumber = 4; - inline float length() const; - inline void set_length(float value); - - // optional float width = 5; - inline bool has_width() const; - inline void clear_width(); - static const int kWidthFieldNumber = 5; - inline float width() const; - inline void set_width(float value); - - // optional float height = 6; - inline bool has_height() const; - inline void clear_height(); - static const int kHeightFieldNumber = 6; - inline float height() const; - inline void set_height(float value); - - // @@protoc_insertion_point(class_scope:px.Obstacle) - private: - inline void set_has_x(); - inline void clear_has_x(); - inline void set_has_y(); - inline void clear_has_y(); - inline void set_has_z(); - inline void clear_has_z(); - inline void set_has_length(); - inline void clear_has_length(); - inline void set_has_width(); - inline void clear_has_width(); - inline void set_has_height(); - inline void clear_has_height(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - float x_; - float y_; - float z_; - float length_; - float width_; - float height_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(6 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static Obstacle* default_instance_; -}; -// ------------------------------------------------------------------- - -class ObstacleList : public ::google::protobuf::Message { - public: - ObstacleList(); - virtual ~ObstacleList(); - - ObstacleList(const ObstacleList& from); - - inline ObstacleList& operator=(const ObstacleList& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const ObstacleList& default_instance(); - - void Swap(ObstacleList* other); - - // implements Message ---------------------------------------------- - - ObstacleList* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const ObstacleList& from); - void MergeFrom(const ObstacleList& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // repeated .px.Obstacle obstacles = 2; - inline int obstacles_size() const; - inline void clear_obstacles(); - static const int kObstaclesFieldNumber = 2; - inline const ::px::Obstacle& obstacles(int index) const; - inline ::px::Obstacle* mutable_obstacles(int index); - inline ::px::Obstacle* add_obstacles(); - inline const ::google::protobuf::RepeatedPtrField< ::px::Obstacle >& - obstacles() const; - inline ::google::protobuf::RepeatedPtrField< ::px::Obstacle >* - mutable_obstacles(); - - // @@protoc_insertion_point(class_scope:px.ObstacleList) - private: - inline void set_has_header(); - inline void clear_has_header(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::RepeatedPtrField< ::px::Obstacle > obstacles_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static ObstacleList* default_instance_; -}; -// ------------------------------------------------------------------- - -class ObstacleMap : public ::google::protobuf::Message { - public: - ObstacleMap(); - virtual ~ObstacleMap(); - - ObstacleMap(const ObstacleMap& from); - - inline ObstacleMap& operator=(const ObstacleMap& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const ObstacleMap& default_instance(); - - void Swap(ObstacleMap* other); - - // implements Message ---------------------------------------------- - - ObstacleMap* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const ObstacleMap& from); - void MergeFrom(const ObstacleMap& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // required int32 type = 2; - inline bool has_type() const; - inline void clear_type(); - static const int kTypeFieldNumber = 2; - inline ::google::protobuf::int32 type() const; - inline void set_type(::google::protobuf::int32 value); - - // optional float resolution = 3; - inline bool has_resolution() const; - inline void clear_resolution(); - static const int kResolutionFieldNumber = 3; - inline float resolution() const; - inline void set_resolution(float value); - - // optional int32 rows = 4; - inline bool has_rows() const; - inline void clear_rows(); - static const int kRowsFieldNumber = 4; - inline ::google::protobuf::int32 rows() const; - inline void set_rows(::google::protobuf::int32 value); - - // optional int32 cols = 5; - inline bool has_cols() const; - inline void clear_cols(); - static const int kColsFieldNumber = 5; - inline ::google::protobuf::int32 cols() const; - inline void set_cols(::google::protobuf::int32 value); - - // optional int32 mapR0 = 6; - inline bool has_mapr0() const; - inline void clear_mapr0(); - static const int kMapR0FieldNumber = 6; - inline ::google::protobuf::int32 mapr0() const; - inline void set_mapr0(::google::protobuf::int32 value); - - // optional int32 mapC0 = 7; - inline bool has_mapc0() const; - inline void clear_mapc0(); - static const int kMapC0FieldNumber = 7; - inline ::google::protobuf::int32 mapc0() const; - inline void set_mapc0(::google::protobuf::int32 value); - - // optional int32 arrayR0 = 8; - inline bool has_arrayr0() const; - inline void clear_arrayr0(); - static const int kArrayR0FieldNumber = 8; - inline ::google::protobuf::int32 arrayr0() const; - inline void set_arrayr0(::google::protobuf::int32 value); - - // optional int32 arrayC0 = 9; - inline bool has_arrayc0() const; - inline void clear_arrayc0(); - static const int kArrayC0FieldNumber = 9; - inline ::google::protobuf::int32 arrayc0() const; - inline void set_arrayc0(::google::protobuf::int32 value); - - // optional bytes data = 10; - inline bool has_data() const; - inline void clear_data(); - static const int kDataFieldNumber = 10; - inline const ::std::string& data() const; - inline void set_data(const ::std::string& value); - inline void set_data(const char* value); - inline void set_data(const void* value, size_t size); - inline ::std::string* mutable_data(); - inline ::std::string* release_data(); - - // @@protoc_insertion_point(class_scope:px.ObstacleMap) - private: - inline void set_has_header(); - inline void clear_has_header(); - inline void set_has_type(); - inline void clear_has_type(); - inline void set_has_resolution(); - inline void clear_has_resolution(); - inline void set_has_rows(); - inline void clear_has_rows(); - inline void set_has_cols(); - inline void clear_has_cols(); - inline void set_has_mapr0(); - inline void clear_has_mapr0(); - inline void set_has_mapc0(); - inline void clear_has_mapc0(); - inline void set_has_arrayr0(); - inline void clear_has_arrayr0(); - inline void set_has_arrayc0(); - inline void clear_has_arrayc0(); - inline void set_has_data(); - inline void clear_has_data(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::int32 type_; - float resolution_; - ::google::protobuf::int32 rows_; - ::google::protobuf::int32 cols_; - ::google::protobuf::int32 mapr0_; - ::google::protobuf::int32 mapc0_; - ::google::protobuf::int32 arrayr0_; - ::google::protobuf::int32 arrayc0_; - ::std::string* data_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(10 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static ObstacleMap* default_instance_; -}; -// ------------------------------------------------------------------- - -class Path : public ::google::protobuf::Message { - public: - Path(); - virtual ~Path(); - - Path(const Path& from); - - inline Path& operator=(const Path& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const Path& default_instance(); - - void Swap(Path* other); - - // implements Message ---------------------------------------------- - - Path* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const Path& from); - void MergeFrom(const Path& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // repeated .px.Waypoint waypoints = 2; - inline int waypoints_size() const; - inline void clear_waypoints(); - static const int kWaypointsFieldNumber = 2; - inline const ::px::Waypoint& waypoints(int index) const; - inline ::px::Waypoint* mutable_waypoints(int index); - inline ::px::Waypoint* add_waypoints(); - inline const ::google::protobuf::RepeatedPtrField< ::px::Waypoint >& - waypoints() const; - inline ::google::protobuf::RepeatedPtrField< ::px::Waypoint >* - mutable_waypoints(); - - // @@protoc_insertion_point(class_scope:px.Path) - private: - inline void set_has_header(); - inline void clear_has_header(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::RepeatedPtrField< ::px::Waypoint > waypoints_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static Path* default_instance_; -}; -// ------------------------------------------------------------------- - -class PointCloudXYZI_PointXYZI : public ::google::protobuf::Message { - public: - PointCloudXYZI_PointXYZI(); - virtual ~PointCloudXYZI_PointXYZI(); - - PointCloudXYZI_PointXYZI(const PointCloudXYZI_PointXYZI& from); - - inline PointCloudXYZI_PointXYZI& operator=(const PointCloudXYZI_PointXYZI& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const PointCloudXYZI_PointXYZI& default_instance(); - - void Swap(PointCloudXYZI_PointXYZI* other); - - // implements Message ---------------------------------------------- - - PointCloudXYZI_PointXYZI* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const PointCloudXYZI_PointXYZI& from); - void MergeFrom(const PointCloudXYZI_PointXYZI& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required float x = 1; - inline bool has_x() const; - inline void clear_x(); - static const int kXFieldNumber = 1; - inline float x() const; - inline void set_x(float value); - - // required float y = 2; - inline bool has_y() const; - inline void clear_y(); - static const int kYFieldNumber = 2; - inline float y() const; - inline void set_y(float value); - - // required float z = 3; - inline bool has_z() const; - inline void clear_z(); - static const int kZFieldNumber = 3; - inline float z() const; - inline void set_z(float value); - - // required float intensity = 4; - inline bool has_intensity() const; - inline void clear_intensity(); - static const int kIntensityFieldNumber = 4; - inline float intensity() const; - inline void set_intensity(float value); - - // @@protoc_insertion_point(class_scope:px.PointCloudXYZI.PointXYZI) - private: - inline void set_has_x(); - inline void clear_has_x(); - inline void set_has_y(); - inline void clear_has_y(); - inline void set_has_z(); - inline void clear_has_z(); - inline void set_has_intensity(); - inline void clear_has_intensity(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - float x_; - float y_; - float z_; - float intensity_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(4 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static PointCloudXYZI_PointXYZI* default_instance_; -}; -// ------------------------------------------------------------------- - -class PointCloudXYZI : public ::google::protobuf::Message { - public: - PointCloudXYZI(); - virtual ~PointCloudXYZI(); - - PointCloudXYZI(const PointCloudXYZI& from); - - inline PointCloudXYZI& operator=(const PointCloudXYZI& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const PointCloudXYZI& default_instance(); - - void Swap(PointCloudXYZI* other); - - // implements Message ---------------------------------------------- - - PointCloudXYZI* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const PointCloudXYZI& from); - void MergeFrom(const PointCloudXYZI& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - typedef PointCloudXYZI_PointXYZI PointXYZI; - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - inline int points_size() const; - inline void clear_points(); - static const int kPointsFieldNumber = 2; - inline const ::px::PointCloudXYZI_PointXYZI& points(int index) const; - inline ::px::PointCloudXYZI_PointXYZI* mutable_points(int index); - inline ::px::PointCloudXYZI_PointXYZI* add_points(); - inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >& - points() const; - inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >* - mutable_points(); - - // @@protoc_insertion_point(class_scope:px.PointCloudXYZI) - private: - inline void set_has_header(); - inline void clear_has_header(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI > points_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static PointCloudXYZI* default_instance_; -}; -// ------------------------------------------------------------------- - -class PointCloudXYZRGB_PointXYZRGB : public ::google::protobuf::Message { - public: - PointCloudXYZRGB_PointXYZRGB(); - virtual ~PointCloudXYZRGB_PointXYZRGB(); - - PointCloudXYZRGB_PointXYZRGB(const PointCloudXYZRGB_PointXYZRGB& from); - - inline PointCloudXYZRGB_PointXYZRGB& operator=(const PointCloudXYZRGB_PointXYZRGB& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const PointCloudXYZRGB_PointXYZRGB& default_instance(); - - void Swap(PointCloudXYZRGB_PointXYZRGB* other); - - // implements Message ---------------------------------------------- - - PointCloudXYZRGB_PointXYZRGB* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const PointCloudXYZRGB_PointXYZRGB& from); - void MergeFrom(const PointCloudXYZRGB_PointXYZRGB& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required float x = 1; - inline bool has_x() const; - inline void clear_x(); - static const int kXFieldNumber = 1; - inline float x() const; - inline void set_x(float value); - - // required float y = 2; - inline bool has_y() const; - inline void clear_y(); - static const int kYFieldNumber = 2; - inline float y() const; - inline void set_y(float value); - - // required float z = 3; - inline bool has_z() const; - inline void clear_z(); - static const int kZFieldNumber = 3; - inline float z() const; - inline void set_z(float value); - - // required float rgb = 4; - inline bool has_rgb() const; - inline void clear_rgb(); - static const int kRgbFieldNumber = 4; - inline float rgb() const; - inline void set_rgb(float value); - - // @@protoc_insertion_point(class_scope:px.PointCloudXYZRGB.PointXYZRGB) - private: - inline void set_has_x(); - inline void clear_has_x(); - inline void set_has_y(); - inline void clear_has_y(); - inline void set_has_z(); - inline void clear_has_z(); - inline void set_has_rgb(); - inline void clear_has_rgb(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - float x_; - float y_; - float z_; - float rgb_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(4 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static PointCloudXYZRGB_PointXYZRGB* default_instance_; -}; -// ------------------------------------------------------------------- - -class PointCloudXYZRGB : public ::google::protobuf::Message { - public: - PointCloudXYZRGB(); - virtual ~PointCloudXYZRGB(); - - PointCloudXYZRGB(const PointCloudXYZRGB& from); - - inline PointCloudXYZRGB& operator=(const PointCloudXYZRGB& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const PointCloudXYZRGB& default_instance(); - - void Swap(PointCloudXYZRGB* other); - - // implements Message ---------------------------------------------- - - PointCloudXYZRGB* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const PointCloudXYZRGB& from); - void MergeFrom(const PointCloudXYZRGB& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - typedef PointCloudXYZRGB_PointXYZRGB PointXYZRGB; - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - inline int points_size() const; - inline void clear_points(); - static const int kPointsFieldNumber = 2; - inline const ::px::PointCloudXYZRGB_PointXYZRGB& points(int index) const; - inline ::px::PointCloudXYZRGB_PointXYZRGB* mutable_points(int index); - inline ::px::PointCloudXYZRGB_PointXYZRGB* add_points(); - inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >& - points() const; - inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >* - mutable_points(); - - // @@protoc_insertion_point(class_scope:px.PointCloudXYZRGB) - private: - inline void set_has_header(); - inline void clear_has_header(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB > points_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(2 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static PointCloudXYZRGB* default_instance_; -}; -// ------------------------------------------------------------------- - -class RGBDImage : public ::google::protobuf::Message { - public: - RGBDImage(); - virtual ~RGBDImage(); - - RGBDImage(const RGBDImage& from); - - inline RGBDImage& operator=(const RGBDImage& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const RGBDImage& default_instance(); - - void Swap(RGBDImage* other); - - // implements Message ---------------------------------------------- - - RGBDImage* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const RGBDImage& from); - void MergeFrom(const RGBDImage& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required .px.HeaderInfo header = 1; - inline bool has_header() const; - inline void clear_header(); - static const int kHeaderFieldNumber = 1; - inline const ::px::HeaderInfo& header() const; - inline ::px::HeaderInfo* mutable_header(); - inline ::px::HeaderInfo* release_header(); - - // required uint32 cols = 2; - inline bool has_cols() const; - inline void clear_cols(); - static const int kColsFieldNumber = 2; - inline ::google::protobuf::uint32 cols() const; - inline void set_cols(::google::protobuf::uint32 value); - - // required uint32 rows = 3; - inline bool has_rows() const; - inline void clear_rows(); - static const int kRowsFieldNumber = 3; - inline ::google::protobuf::uint32 rows() const; - inline void set_rows(::google::protobuf::uint32 value); - - // required uint32 step1 = 4; - inline bool has_step1() const; - inline void clear_step1(); - static const int kStep1FieldNumber = 4; - inline ::google::protobuf::uint32 step1() const; - inline void set_step1(::google::protobuf::uint32 value); - - // required uint32 type1 = 5; - inline bool has_type1() const; - inline void clear_type1(); - static const int kType1FieldNumber = 5; - inline ::google::protobuf::uint32 type1() const; - inline void set_type1(::google::protobuf::uint32 value); - - // required bytes imageData1 = 6; - inline bool has_imagedata1() const; - inline void clear_imagedata1(); - static const int kImageData1FieldNumber = 6; - inline const ::std::string& imagedata1() const; - inline void set_imagedata1(const ::std::string& value); - inline void set_imagedata1(const char* value); - inline void set_imagedata1(const void* value, size_t size); - inline ::std::string* mutable_imagedata1(); - inline ::std::string* release_imagedata1(); - - // required uint32 step2 = 7; - inline bool has_step2() const; - inline void clear_step2(); - static const int kStep2FieldNumber = 7; - inline ::google::protobuf::uint32 step2() const; - inline void set_step2(::google::protobuf::uint32 value); - - // required uint32 type2 = 8; - inline bool has_type2() const; - inline void clear_type2(); - static const int kType2FieldNumber = 8; - inline ::google::protobuf::uint32 type2() const; - inline void set_type2(::google::protobuf::uint32 value); - - // required bytes imageData2 = 9; - inline bool has_imagedata2() const; - inline void clear_imagedata2(); - static const int kImageData2FieldNumber = 9; - inline const ::std::string& imagedata2() const; - inline void set_imagedata2(const ::std::string& value); - inline void set_imagedata2(const char* value); - inline void set_imagedata2(const void* value, size_t size); - inline ::std::string* mutable_imagedata2(); - inline ::std::string* release_imagedata2(); - - // optional uint32 camera_config = 10; - inline bool has_camera_config() const; - inline void clear_camera_config(); - static const int kCameraConfigFieldNumber = 10; - inline ::google::protobuf::uint32 camera_config() const; - inline void set_camera_config(::google::protobuf::uint32 value); - - // optional uint32 camera_type = 11; - inline bool has_camera_type() const; - inline void clear_camera_type(); - static const int kCameraTypeFieldNumber = 11; - inline ::google::protobuf::uint32 camera_type() const; - inline void set_camera_type(::google::protobuf::uint32 value); - - // optional float roll = 12; - inline bool has_roll() const; - inline void clear_roll(); - static const int kRollFieldNumber = 12; - inline float roll() const; - inline void set_roll(float value); - - // optional float pitch = 13; - inline bool has_pitch() const; - inline void clear_pitch(); - static const int kPitchFieldNumber = 13; - inline float pitch() const; - inline void set_pitch(float value); - - // optional float yaw = 14; - inline bool has_yaw() const; - inline void clear_yaw(); - static const int kYawFieldNumber = 14; - inline float yaw() const; - inline void set_yaw(float value); - - // optional float lon = 15; - inline bool has_lon() const; - inline void clear_lon(); - static const int kLonFieldNumber = 15; - inline float lon() const; - inline void set_lon(float value); - - // optional float lat = 16; - inline bool has_lat() const; - inline void clear_lat(); - static const int kLatFieldNumber = 16; - inline float lat() const; - inline void set_lat(float value); - - // optional float alt = 17; - inline bool has_alt() const; - inline void clear_alt(); - static const int kAltFieldNumber = 17; - inline float alt() const; - inline void set_alt(float value); - - // optional float ground_x = 18; - inline bool has_ground_x() const; - inline void clear_ground_x(); - static const int kGroundXFieldNumber = 18; - inline float ground_x() const; - inline void set_ground_x(float value); - - // optional float ground_y = 19; - inline bool has_ground_y() const; - inline void clear_ground_y(); - static const int kGroundYFieldNumber = 19; - inline float ground_y() const; - inline void set_ground_y(float value); - - // optional float ground_z = 20; - inline bool has_ground_z() const; - inline void clear_ground_z(); - static const int kGroundZFieldNumber = 20; - inline float ground_z() const; - inline void set_ground_z(float value); - - // repeated float camera_matrix = 21; - inline int camera_matrix_size() const; - inline void clear_camera_matrix(); - static const int kCameraMatrixFieldNumber = 21; - inline float camera_matrix(int index) const; - inline void set_camera_matrix(int index, float value); - inline void add_camera_matrix(float value); - inline const ::google::protobuf::RepeatedField< float >& - camera_matrix() const; - inline ::google::protobuf::RepeatedField< float >* - mutable_camera_matrix(); - - // @@protoc_insertion_point(class_scope:px.RGBDImage) - private: - inline void set_has_header(); - inline void clear_has_header(); - inline void set_has_cols(); - inline void clear_has_cols(); - inline void set_has_rows(); - inline void clear_has_rows(); - inline void set_has_step1(); - inline void clear_has_step1(); - inline void set_has_type1(); - inline void clear_has_type1(); - inline void set_has_imagedata1(); - inline void clear_has_imagedata1(); - inline void set_has_step2(); - inline void clear_has_step2(); - inline void set_has_type2(); - inline void clear_has_type2(); - inline void set_has_imagedata2(); - inline void clear_has_imagedata2(); - inline void set_has_camera_config(); - inline void clear_has_camera_config(); - inline void set_has_camera_type(); - inline void clear_has_camera_type(); - inline void set_has_roll(); - inline void clear_has_roll(); - inline void set_has_pitch(); - inline void clear_has_pitch(); - inline void set_has_yaw(); - inline void clear_has_yaw(); - inline void set_has_lon(); - inline void clear_has_lon(); - inline void set_has_lat(); - inline void clear_has_lat(); - inline void set_has_alt(); - inline void clear_has_alt(); - inline void set_has_ground_x(); - inline void clear_has_ground_x(); - inline void set_has_ground_y(); - inline void clear_has_ground_y(); - inline void set_has_ground_z(); - inline void clear_has_ground_z(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - ::px::HeaderInfo* header_; - ::google::protobuf::uint32 cols_; - ::google::protobuf::uint32 rows_; - ::google::protobuf::uint32 step1_; - ::google::protobuf::uint32 type1_; - ::std::string* imagedata1_; - ::google::protobuf::uint32 step2_; - ::google::protobuf::uint32 type2_; - ::std::string* imagedata2_; - ::google::protobuf::uint32 camera_config_; - ::google::protobuf::uint32 camera_type_; - float roll_; - float pitch_; - float yaw_; - float lon_; - float lat_; - float alt_; - float ground_x_; - float ground_y_; - ::google::protobuf::RepeatedField< float > camera_matrix_; - float ground_z_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(21 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static RGBDImage* default_instance_; -}; -// ------------------------------------------------------------------- - -class Waypoint : public ::google::protobuf::Message { - public: - Waypoint(); - virtual ~Waypoint(); - - Waypoint(const Waypoint& from); - - inline Waypoint& operator=(const Waypoint& from) { - CopyFrom(from); - return *this; - } - - inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const { - return _unknown_fields_; - } - - inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() { - return &_unknown_fields_; - } - - static const ::google::protobuf::Descriptor* descriptor(); - static const Waypoint& default_instance(); - - void Swap(Waypoint* other); - - // implements Message ---------------------------------------------- - - Waypoint* New() const; - void CopyFrom(const ::google::protobuf::Message& from); - void MergeFrom(const ::google::protobuf::Message& from); - void CopyFrom(const Waypoint& from); - void MergeFrom(const Waypoint& from); - void Clear(); - bool IsInitialized() const; - - int ByteSize() const; - bool MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input); - void SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const; - ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const; - int GetCachedSize() const { return _cached_size_; } - private: - void SharedCtor(); - void SharedDtor(); - void SetCachedSize(int size) const; - public: - - ::google::protobuf::Metadata GetMetadata() const; - - // nested types ---------------------------------------------------- - - // accessors ------------------------------------------------------- - - // required double x = 1; - inline bool has_x() const; - inline void clear_x(); - static const int kXFieldNumber = 1; - inline double x() const; - inline void set_x(double value); - - // required double y = 2; - inline bool has_y() const; - inline void clear_y(); - static const int kYFieldNumber = 2; - inline double y() const; - inline void set_y(double value); - - // optional double z = 3; - inline bool has_z() const; - inline void clear_z(); - static const int kZFieldNumber = 3; - inline double z() const; - inline void set_z(double value); - - // optional double roll = 4; - inline bool has_roll() const; - inline void clear_roll(); - static const int kRollFieldNumber = 4; - inline double roll() const; - inline void set_roll(double value); - - // optional double pitch = 5; - inline bool has_pitch() const; - inline void clear_pitch(); - static const int kPitchFieldNumber = 5; - inline double pitch() const; - inline void set_pitch(double value); - - // optional double yaw = 6; - inline bool has_yaw() const; - inline void clear_yaw(); - static const int kYawFieldNumber = 6; - inline double yaw() const; - inline void set_yaw(double value); - - // @@protoc_insertion_point(class_scope:px.Waypoint) - private: - inline void set_has_x(); - inline void clear_has_x(); - inline void set_has_y(); - inline void clear_has_y(); - inline void set_has_z(); - inline void clear_has_z(); - inline void set_has_roll(); - inline void clear_has_roll(); - inline void set_has_pitch(); - inline void clear_has_pitch(); - inline void set_has_yaw(); - inline void clear_has_yaw(); - - ::google::protobuf::UnknownFieldSet _unknown_fields_; - - double x_; - double y_; - double z_; - double roll_; - double pitch_; - double yaw_; - - mutable int _cached_size_; - ::google::protobuf::uint32 _has_bits_[(6 + 31) / 32]; - - friend void protobuf_AddDesc_pixhawk_2eproto(); - friend void protobuf_AssignDesc_pixhawk_2eproto(); - friend void protobuf_ShutdownFile_pixhawk_2eproto(); - - void InitAsDefaultInstance(); - static Waypoint* default_instance_; -}; -// =================================================================== - - -// =================================================================== - -// HeaderInfo - -// required int32 source_sysid = 1; -inline bool HeaderInfo::has_source_sysid() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void HeaderInfo::set_has_source_sysid() { - _has_bits_[0] |= 0x00000001u; -} -inline void HeaderInfo::clear_has_source_sysid() { - _has_bits_[0] &= ~0x00000001u; -} -inline void HeaderInfo::clear_source_sysid() { - source_sysid_ = 0; - clear_has_source_sysid(); -} -inline ::google::protobuf::int32 HeaderInfo::source_sysid() const { - return source_sysid_; -} -inline void HeaderInfo::set_source_sysid(::google::protobuf::int32 value) { - set_has_source_sysid(); - source_sysid_ = value; -} - -// required int32 source_compid = 2; -inline bool HeaderInfo::has_source_compid() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void HeaderInfo::set_has_source_compid() { - _has_bits_[0] |= 0x00000002u; -} -inline void HeaderInfo::clear_has_source_compid() { - _has_bits_[0] &= ~0x00000002u; -} -inline void HeaderInfo::clear_source_compid() { - source_compid_ = 0; - clear_has_source_compid(); -} -inline ::google::protobuf::int32 HeaderInfo::source_compid() const { - return source_compid_; -} -inline void HeaderInfo::set_source_compid(::google::protobuf::int32 value) { - set_has_source_compid(); - source_compid_ = value; -} - -// required double timestamp = 3; -inline bool HeaderInfo::has_timestamp() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void HeaderInfo::set_has_timestamp() { - _has_bits_[0] |= 0x00000004u; -} -inline void HeaderInfo::clear_has_timestamp() { - _has_bits_[0] &= ~0x00000004u; -} -inline void HeaderInfo::clear_timestamp() { - timestamp_ = 0; - clear_has_timestamp(); -} -inline double HeaderInfo::timestamp() const { - return timestamp_; -} -inline void HeaderInfo::set_timestamp(double value) { - set_has_timestamp(); - timestamp_ = value; -} - -// ------------------------------------------------------------------- - -// GLOverlay - -// required .px.HeaderInfo header = 1; -inline bool GLOverlay::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void GLOverlay::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void GLOverlay::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void GLOverlay::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& GLOverlay::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* GLOverlay::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* GLOverlay::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// optional string name = 2; -inline bool GLOverlay::has_name() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void GLOverlay::set_has_name() { - _has_bits_[0] |= 0x00000002u; -} -inline void GLOverlay::clear_has_name() { - _has_bits_[0] &= ~0x00000002u; -} -inline void GLOverlay::clear_name() { - if (name_ != &::google::protobuf::internal::kEmptyString) { - name_->clear(); - } - clear_has_name(); -} -inline const ::std::string& GLOverlay::name() const { - return *name_; -} -inline void GLOverlay::set_name(const ::std::string& value) { - set_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - name_ = new ::std::string; - } - name_->assign(value); -} -inline void GLOverlay::set_name(const char* value) { - set_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - name_ = new ::std::string; - } - name_->assign(value); -} -inline void GLOverlay::set_name(const char* value, size_t size) { - set_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - name_ = new ::std::string; - } - name_->assign(reinterpret_cast(value), size); -} -inline ::std::string* GLOverlay::mutable_name() { - set_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - name_ = new ::std::string; - } - return name_; -} -inline ::std::string* GLOverlay::release_name() { - clear_has_name(); - if (name_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = name_; - name_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; -inline bool GLOverlay::has_coordinateframetype() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void GLOverlay::set_has_coordinateframetype() { - _has_bits_[0] |= 0x00000004u; -} -inline void GLOverlay::clear_has_coordinateframetype() { - _has_bits_[0] &= ~0x00000004u; -} -inline void GLOverlay::clear_coordinateframetype() { - coordinateframetype_ = 0; - clear_has_coordinateframetype(); -} -inline ::px::GLOverlay_CoordinateFrameType GLOverlay::coordinateframetype() const { - return static_cast< ::px::GLOverlay_CoordinateFrameType >(coordinateframetype_); -} -inline void GLOverlay::set_coordinateframetype(::px::GLOverlay_CoordinateFrameType value) { - GOOGLE_DCHECK(::px::GLOverlay_CoordinateFrameType_IsValid(value)); - set_has_coordinateframetype(); - coordinateframetype_ = value; -} - -// optional double origin_x = 4; -inline bool GLOverlay::has_origin_x() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void GLOverlay::set_has_origin_x() { - _has_bits_[0] |= 0x00000008u; -} -inline void GLOverlay::clear_has_origin_x() { - _has_bits_[0] &= ~0x00000008u; -} -inline void GLOverlay::clear_origin_x() { - origin_x_ = 0; - clear_has_origin_x(); -} -inline double GLOverlay::origin_x() const { - return origin_x_; -} -inline void GLOverlay::set_origin_x(double value) { - set_has_origin_x(); - origin_x_ = value; -} - -// optional double origin_y = 5; -inline bool GLOverlay::has_origin_y() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void GLOverlay::set_has_origin_y() { - _has_bits_[0] |= 0x00000010u; -} -inline void GLOverlay::clear_has_origin_y() { - _has_bits_[0] &= ~0x00000010u; -} -inline void GLOverlay::clear_origin_y() { - origin_y_ = 0; - clear_has_origin_y(); -} -inline double GLOverlay::origin_y() const { - return origin_y_; -} -inline void GLOverlay::set_origin_y(double value) { - set_has_origin_y(); - origin_y_ = value; -} - -// optional double origin_z = 6; -inline bool GLOverlay::has_origin_z() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void GLOverlay::set_has_origin_z() { - _has_bits_[0] |= 0x00000020u; -} -inline void GLOverlay::clear_has_origin_z() { - _has_bits_[0] &= ~0x00000020u; -} -inline void GLOverlay::clear_origin_z() { - origin_z_ = 0; - clear_has_origin_z(); -} -inline double GLOverlay::origin_z() const { - return origin_z_; -} -inline void GLOverlay::set_origin_z(double value) { - set_has_origin_z(); - origin_z_ = value; -} - -// optional bytes data = 7; -inline bool GLOverlay::has_data() const { - return (_has_bits_[0] & 0x00000040u) != 0; -} -inline void GLOverlay::set_has_data() { - _has_bits_[0] |= 0x00000040u; -} -inline void GLOverlay::clear_has_data() { - _has_bits_[0] &= ~0x00000040u; -} -inline void GLOverlay::clear_data() { - if (data_ != &::google::protobuf::internal::kEmptyString) { - data_->clear(); - } - clear_has_data(); -} -inline const ::std::string& GLOverlay::data() const { - return *data_; -} -inline void GLOverlay::set_data(const ::std::string& value) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(value); -} -inline void GLOverlay::set_data(const char* value) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(value); -} -inline void GLOverlay::set_data(const void* value, size_t size) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(reinterpret_cast(value), size); -} -inline ::std::string* GLOverlay::mutable_data() { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - return data_; -} -inline ::std::string* GLOverlay::release_data() { - clear_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = data_; - data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// ------------------------------------------------------------------- - -// Obstacle - -// optional float x = 1; -inline bool Obstacle::has_x() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void Obstacle::set_has_x() { - _has_bits_[0] |= 0x00000001u; -} -inline void Obstacle::clear_has_x() { - _has_bits_[0] &= ~0x00000001u; -} -inline void Obstacle::clear_x() { - x_ = 0; - clear_has_x(); -} -inline float Obstacle::x() const { - return x_; -} -inline void Obstacle::set_x(float value) { - set_has_x(); - x_ = value; -} - -// optional float y = 2; -inline bool Obstacle::has_y() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void Obstacle::set_has_y() { - _has_bits_[0] |= 0x00000002u; -} -inline void Obstacle::clear_has_y() { - _has_bits_[0] &= ~0x00000002u; -} -inline void Obstacle::clear_y() { - y_ = 0; - clear_has_y(); -} -inline float Obstacle::y() const { - return y_; -} -inline void Obstacle::set_y(float value) { - set_has_y(); - y_ = value; -} - -// optional float z = 3; -inline bool Obstacle::has_z() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void Obstacle::set_has_z() { - _has_bits_[0] |= 0x00000004u; -} -inline void Obstacle::clear_has_z() { - _has_bits_[0] &= ~0x00000004u; -} -inline void Obstacle::clear_z() { - z_ = 0; - clear_has_z(); -} -inline float Obstacle::z() const { - return z_; -} -inline void Obstacle::set_z(float value) { - set_has_z(); - z_ = value; -} - -// optional float length = 4; -inline bool Obstacle::has_length() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void Obstacle::set_has_length() { - _has_bits_[0] |= 0x00000008u; -} -inline void Obstacle::clear_has_length() { - _has_bits_[0] &= ~0x00000008u; -} -inline void Obstacle::clear_length() { - length_ = 0; - clear_has_length(); -} -inline float Obstacle::length() const { - return length_; -} -inline void Obstacle::set_length(float value) { - set_has_length(); - length_ = value; -} - -// optional float width = 5; -inline bool Obstacle::has_width() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void Obstacle::set_has_width() { - _has_bits_[0] |= 0x00000010u; -} -inline void Obstacle::clear_has_width() { - _has_bits_[0] &= ~0x00000010u; -} -inline void Obstacle::clear_width() { - width_ = 0; - clear_has_width(); -} -inline float Obstacle::width() const { - return width_; -} -inline void Obstacle::set_width(float value) { - set_has_width(); - width_ = value; -} - -// optional float height = 6; -inline bool Obstacle::has_height() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void Obstacle::set_has_height() { - _has_bits_[0] |= 0x00000020u; -} -inline void Obstacle::clear_has_height() { - _has_bits_[0] &= ~0x00000020u; -} -inline void Obstacle::clear_height() { - height_ = 0; - clear_has_height(); -} -inline float Obstacle::height() const { - return height_; -} -inline void Obstacle::set_height(float value) { - set_has_height(); - height_ = value; -} - -// ------------------------------------------------------------------- - -// ObstacleList - -// required .px.HeaderInfo header = 1; -inline bool ObstacleList::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void ObstacleList::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void ObstacleList::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void ObstacleList::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& ObstacleList::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* ObstacleList::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* ObstacleList::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// repeated .px.Obstacle obstacles = 2; -inline int ObstacleList::obstacles_size() const { - return obstacles_.size(); -} -inline void ObstacleList::clear_obstacles() { - obstacles_.Clear(); -} -inline const ::px::Obstacle& ObstacleList::obstacles(int index) const { - return obstacles_.Get(index); -} -inline ::px::Obstacle* ObstacleList::mutable_obstacles(int index) { - return obstacles_.Mutable(index); -} -inline ::px::Obstacle* ObstacleList::add_obstacles() { - return obstacles_.Add(); -} -inline const ::google::protobuf::RepeatedPtrField< ::px::Obstacle >& -ObstacleList::obstacles() const { - return obstacles_; -} -inline ::google::protobuf::RepeatedPtrField< ::px::Obstacle >* -ObstacleList::mutable_obstacles() { - return &obstacles_; -} - -// ------------------------------------------------------------------- - -// ObstacleMap - -// required .px.HeaderInfo header = 1; -inline bool ObstacleMap::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void ObstacleMap::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void ObstacleMap::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void ObstacleMap::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& ObstacleMap::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* ObstacleMap::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* ObstacleMap::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// required int32 type = 2; -inline bool ObstacleMap::has_type() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void ObstacleMap::set_has_type() { - _has_bits_[0] |= 0x00000002u; -} -inline void ObstacleMap::clear_has_type() { - _has_bits_[0] &= ~0x00000002u; -} -inline void ObstacleMap::clear_type() { - type_ = 0; - clear_has_type(); -} -inline ::google::protobuf::int32 ObstacleMap::type() const { - return type_; -} -inline void ObstacleMap::set_type(::google::protobuf::int32 value) { - set_has_type(); - type_ = value; -} - -// optional float resolution = 3; -inline bool ObstacleMap::has_resolution() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void ObstacleMap::set_has_resolution() { - _has_bits_[0] |= 0x00000004u; -} -inline void ObstacleMap::clear_has_resolution() { - _has_bits_[0] &= ~0x00000004u; -} -inline void ObstacleMap::clear_resolution() { - resolution_ = 0; - clear_has_resolution(); -} -inline float ObstacleMap::resolution() const { - return resolution_; -} -inline void ObstacleMap::set_resolution(float value) { - set_has_resolution(); - resolution_ = value; -} - -// optional int32 rows = 4; -inline bool ObstacleMap::has_rows() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void ObstacleMap::set_has_rows() { - _has_bits_[0] |= 0x00000008u; -} -inline void ObstacleMap::clear_has_rows() { - _has_bits_[0] &= ~0x00000008u; -} -inline void ObstacleMap::clear_rows() { - rows_ = 0; - clear_has_rows(); -} -inline ::google::protobuf::int32 ObstacleMap::rows() const { - return rows_; -} -inline void ObstacleMap::set_rows(::google::protobuf::int32 value) { - set_has_rows(); - rows_ = value; -} - -// optional int32 cols = 5; -inline bool ObstacleMap::has_cols() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void ObstacleMap::set_has_cols() { - _has_bits_[0] |= 0x00000010u; -} -inline void ObstacleMap::clear_has_cols() { - _has_bits_[0] &= ~0x00000010u; -} -inline void ObstacleMap::clear_cols() { - cols_ = 0; - clear_has_cols(); -} -inline ::google::protobuf::int32 ObstacleMap::cols() const { - return cols_; -} -inline void ObstacleMap::set_cols(::google::protobuf::int32 value) { - set_has_cols(); - cols_ = value; -} - -// optional int32 mapR0 = 6; -inline bool ObstacleMap::has_mapr0() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void ObstacleMap::set_has_mapr0() { - _has_bits_[0] |= 0x00000020u; -} -inline void ObstacleMap::clear_has_mapr0() { - _has_bits_[0] &= ~0x00000020u; -} -inline void ObstacleMap::clear_mapr0() { - mapr0_ = 0; - clear_has_mapr0(); -} -inline ::google::protobuf::int32 ObstacleMap::mapr0() const { - return mapr0_; -} -inline void ObstacleMap::set_mapr0(::google::protobuf::int32 value) { - set_has_mapr0(); - mapr0_ = value; -} - -// optional int32 mapC0 = 7; -inline bool ObstacleMap::has_mapc0() const { - return (_has_bits_[0] & 0x00000040u) != 0; -} -inline void ObstacleMap::set_has_mapc0() { - _has_bits_[0] |= 0x00000040u; -} -inline void ObstacleMap::clear_has_mapc0() { - _has_bits_[0] &= ~0x00000040u; -} -inline void ObstacleMap::clear_mapc0() { - mapc0_ = 0; - clear_has_mapc0(); -} -inline ::google::protobuf::int32 ObstacleMap::mapc0() const { - return mapc0_; -} -inline void ObstacleMap::set_mapc0(::google::protobuf::int32 value) { - set_has_mapc0(); - mapc0_ = value; -} - -// optional int32 arrayR0 = 8; -inline bool ObstacleMap::has_arrayr0() const { - return (_has_bits_[0] & 0x00000080u) != 0; -} -inline void ObstacleMap::set_has_arrayr0() { - _has_bits_[0] |= 0x00000080u; -} -inline void ObstacleMap::clear_has_arrayr0() { - _has_bits_[0] &= ~0x00000080u; -} -inline void ObstacleMap::clear_arrayr0() { - arrayr0_ = 0; - clear_has_arrayr0(); -} -inline ::google::protobuf::int32 ObstacleMap::arrayr0() const { - return arrayr0_; -} -inline void ObstacleMap::set_arrayr0(::google::protobuf::int32 value) { - set_has_arrayr0(); - arrayr0_ = value; -} - -// optional int32 arrayC0 = 9; -inline bool ObstacleMap::has_arrayc0() const { - return (_has_bits_[0] & 0x00000100u) != 0; -} -inline void ObstacleMap::set_has_arrayc0() { - _has_bits_[0] |= 0x00000100u; -} -inline void ObstacleMap::clear_has_arrayc0() { - _has_bits_[0] &= ~0x00000100u; -} -inline void ObstacleMap::clear_arrayc0() { - arrayc0_ = 0; - clear_has_arrayc0(); -} -inline ::google::protobuf::int32 ObstacleMap::arrayc0() const { - return arrayc0_; -} -inline void ObstacleMap::set_arrayc0(::google::protobuf::int32 value) { - set_has_arrayc0(); - arrayc0_ = value; -} - -// optional bytes data = 10; -inline bool ObstacleMap::has_data() const { - return (_has_bits_[0] & 0x00000200u) != 0; -} -inline void ObstacleMap::set_has_data() { - _has_bits_[0] |= 0x00000200u; -} -inline void ObstacleMap::clear_has_data() { - _has_bits_[0] &= ~0x00000200u; -} -inline void ObstacleMap::clear_data() { - if (data_ != &::google::protobuf::internal::kEmptyString) { - data_->clear(); - } - clear_has_data(); -} -inline const ::std::string& ObstacleMap::data() const { - return *data_; -} -inline void ObstacleMap::set_data(const ::std::string& value) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(value); -} -inline void ObstacleMap::set_data(const char* value) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(value); -} -inline void ObstacleMap::set_data(const void* value, size_t size) { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - data_->assign(reinterpret_cast(value), size); -} -inline ::std::string* ObstacleMap::mutable_data() { - set_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - data_ = new ::std::string; - } - return data_; -} -inline ::std::string* ObstacleMap::release_data() { - clear_has_data(); - if (data_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = data_; - data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// ------------------------------------------------------------------- - -// Path - -// required .px.HeaderInfo header = 1; -inline bool Path::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void Path::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void Path::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void Path::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& Path::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* Path::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* Path::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// repeated .px.Waypoint waypoints = 2; -inline int Path::waypoints_size() const { - return waypoints_.size(); -} -inline void Path::clear_waypoints() { - waypoints_.Clear(); -} -inline const ::px::Waypoint& Path::waypoints(int index) const { - return waypoints_.Get(index); -} -inline ::px::Waypoint* Path::mutable_waypoints(int index) { - return waypoints_.Mutable(index); -} -inline ::px::Waypoint* Path::add_waypoints() { - return waypoints_.Add(); -} -inline const ::google::protobuf::RepeatedPtrField< ::px::Waypoint >& -Path::waypoints() const { - return waypoints_; -} -inline ::google::protobuf::RepeatedPtrField< ::px::Waypoint >* -Path::mutable_waypoints() { - return &waypoints_; -} - -// ------------------------------------------------------------------- - -// PointCloudXYZI_PointXYZI - -// required float x = 1; -inline bool PointCloudXYZI_PointXYZI::has_x() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void PointCloudXYZI_PointXYZI::set_has_x() { - _has_bits_[0] |= 0x00000001u; -} -inline void PointCloudXYZI_PointXYZI::clear_has_x() { - _has_bits_[0] &= ~0x00000001u; -} -inline void PointCloudXYZI_PointXYZI::clear_x() { - x_ = 0; - clear_has_x(); -} -inline float PointCloudXYZI_PointXYZI::x() const { - return x_; -} -inline void PointCloudXYZI_PointXYZI::set_x(float value) { - set_has_x(); - x_ = value; -} - -// required float y = 2; -inline bool PointCloudXYZI_PointXYZI::has_y() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void PointCloudXYZI_PointXYZI::set_has_y() { - _has_bits_[0] |= 0x00000002u; -} -inline void PointCloudXYZI_PointXYZI::clear_has_y() { - _has_bits_[0] &= ~0x00000002u; -} -inline void PointCloudXYZI_PointXYZI::clear_y() { - y_ = 0; - clear_has_y(); -} -inline float PointCloudXYZI_PointXYZI::y() const { - return y_; -} -inline void PointCloudXYZI_PointXYZI::set_y(float value) { - set_has_y(); - y_ = value; -} - -// required float z = 3; -inline bool PointCloudXYZI_PointXYZI::has_z() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void PointCloudXYZI_PointXYZI::set_has_z() { - _has_bits_[0] |= 0x00000004u; -} -inline void PointCloudXYZI_PointXYZI::clear_has_z() { - _has_bits_[0] &= ~0x00000004u; -} -inline void PointCloudXYZI_PointXYZI::clear_z() { - z_ = 0; - clear_has_z(); -} -inline float PointCloudXYZI_PointXYZI::z() const { - return z_; -} -inline void PointCloudXYZI_PointXYZI::set_z(float value) { - set_has_z(); - z_ = value; -} - -// required float intensity = 4; -inline bool PointCloudXYZI_PointXYZI::has_intensity() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void PointCloudXYZI_PointXYZI::set_has_intensity() { - _has_bits_[0] |= 0x00000008u; -} -inline void PointCloudXYZI_PointXYZI::clear_has_intensity() { - _has_bits_[0] &= ~0x00000008u; -} -inline void PointCloudXYZI_PointXYZI::clear_intensity() { - intensity_ = 0; - clear_has_intensity(); -} -inline float PointCloudXYZI_PointXYZI::intensity() const { - return intensity_; -} -inline void PointCloudXYZI_PointXYZI::set_intensity(float value) { - set_has_intensity(); - intensity_ = value; -} - -// ------------------------------------------------------------------- - -// PointCloudXYZI - -// required .px.HeaderInfo header = 1; -inline bool PointCloudXYZI::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void PointCloudXYZI::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void PointCloudXYZI::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void PointCloudXYZI::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& PointCloudXYZI::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* PointCloudXYZI::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* PointCloudXYZI::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// repeated .px.PointCloudXYZI.PointXYZI points = 2; -inline int PointCloudXYZI::points_size() const { - return points_.size(); -} -inline void PointCloudXYZI::clear_points() { - points_.Clear(); -} -inline const ::px::PointCloudXYZI_PointXYZI& PointCloudXYZI::points(int index) const { - return points_.Get(index); -} -inline ::px::PointCloudXYZI_PointXYZI* PointCloudXYZI::mutable_points(int index) { - return points_.Mutable(index); -} -inline ::px::PointCloudXYZI_PointXYZI* PointCloudXYZI::add_points() { - return points_.Add(); -} -inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >& -PointCloudXYZI::points() const { - return points_; -} -inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZI_PointXYZI >* -PointCloudXYZI::mutable_points() { - return &points_; -} - -// ------------------------------------------------------------------- - -// PointCloudXYZRGB_PointXYZRGB - -// required float x = 1; -inline bool PointCloudXYZRGB_PointXYZRGB::has_x() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_has_x() { - _has_bits_[0] |= 0x00000001u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_has_x() { - _has_bits_[0] &= ~0x00000001u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_x() { - x_ = 0; - clear_has_x(); -} -inline float PointCloudXYZRGB_PointXYZRGB::x() const { - return x_; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_x(float value) { - set_has_x(); - x_ = value; -} - -// required float y = 2; -inline bool PointCloudXYZRGB_PointXYZRGB::has_y() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_has_y() { - _has_bits_[0] |= 0x00000002u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_has_y() { - _has_bits_[0] &= ~0x00000002u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_y() { - y_ = 0; - clear_has_y(); -} -inline float PointCloudXYZRGB_PointXYZRGB::y() const { - return y_; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_y(float value) { - set_has_y(); - y_ = value; -} - -// required float z = 3; -inline bool PointCloudXYZRGB_PointXYZRGB::has_z() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_has_z() { - _has_bits_[0] |= 0x00000004u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_has_z() { - _has_bits_[0] &= ~0x00000004u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_z() { - z_ = 0; - clear_has_z(); -} -inline float PointCloudXYZRGB_PointXYZRGB::z() const { - return z_; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_z(float value) { - set_has_z(); - z_ = value; -} - -// required float rgb = 4; -inline bool PointCloudXYZRGB_PointXYZRGB::has_rgb() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_has_rgb() { - _has_bits_[0] |= 0x00000008u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_has_rgb() { - _has_bits_[0] &= ~0x00000008u; -} -inline void PointCloudXYZRGB_PointXYZRGB::clear_rgb() { - rgb_ = 0; - clear_has_rgb(); -} -inline float PointCloudXYZRGB_PointXYZRGB::rgb() const { - return rgb_; -} -inline void PointCloudXYZRGB_PointXYZRGB::set_rgb(float value) { - set_has_rgb(); - rgb_ = value; -} - -// ------------------------------------------------------------------- - -// PointCloudXYZRGB - -// required .px.HeaderInfo header = 1; -inline bool PointCloudXYZRGB::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void PointCloudXYZRGB::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void PointCloudXYZRGB::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void PointCloudXYZRGB::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& PointCloudXYZRGB::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* PointCloudXYZRGB::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* PointCloudXYZRGB::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; -inline int PointCloudXYZRGB::points_size() const { - return points_.size(); -} -inline void PointCloudXYZRGB::clear_points() { - points_.Clear(); -} -inline const ::px::PointCloudXYZRGB_PointXYZRGB& PointCloudXYZRGB::points(int index) const { - return points_.Get(index); -} -inline ::px::PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB::mutable_points(int index) { - return points_.Mutable(index); -} -inline ::px::PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB::add_points() { - return points_.Add(); -} -inline const ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >& -PointCloudXYZRGB::points() const { - return points_; -} -inline ::google::protobuf::RepeatedPtrField< ::px::PointCloudXYZRGB_PointXYZRGB >* -PointCloudXYZRGB::mutable_points() { - return &points_; -} - -// ------------------------------------------------------------------- - -// RGBDImage - -// required .px.HeaderInfo header = 1; -inline bool RGBDImage::has_header() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void RGBDImage::set_has_header() { - _has_bits_[0] |= 0x00000001u; -} -inline void RGBDImage::clear_has_header() { - _has_bits_[0] &= ~0x00000001u; -} -inline void RGBDImage::clear_header() { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - clear_has_header(); -} -inline const ::px::HeaderInfo& RGBDImage::header() const { - return header_ != NULL ? *header_ : *default_instance_->header_; -} -inline ::px::HeaderInfo* RGBDImage::mutable_header() { - set_has_header(); - if (header_ == NULL) header_ = new ::px::HeaderInfo; - return header_; -} -inline ::px::HeaderInfo* RGBDImage::release_header() { - clear_has_header(); - ::px::HeaderInfo* temp = header_; - header_ = NULL; - return temp; -} - -// required uint32 cols = 2; -inline bool RGBDImage::has_cols() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void RGBDImage::set_has_cols() { - _has_bits_[0] |= 0x00000002u; -} -inline void RGBDImage::clear_has_cols() { - _has_bits_[0] &= ~0x00000002u; -} -inline void RGBDImage::clear_cols() { - cols_ = 0u; - clear_has_cols(); -} -inline ::google::protobuf::uint32 RGBDImage::cols() const { - return cols_; -} -inline void RGBDImage::set_cols(::google::protobuf::uint32 value) { - set_has_cols(); - cols_ = value; -} - -// required uint32 rows = 3; -inline bool RGBDImage::has_rows() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void RGBDImage::set_has_rows() { - _has_bits_[0] |= 0x00000004u; -} -inline void RGBDImage::clear_has_rows() { - _has_bits_[0] &= ~0x00000004u; -} -inline void RGBDImage::clear_rows() { - rows_ = 0u; - clear_has_rows(); -} -inline ::google::protobuf::uint32 RGBDImage::rows() const { - return rows_; -} -inline void RGBDImage::set_rows(::google::protobuf::uint32 value) { - set_has_rows(); - rows_ = value; -} - -// required uint32 step1 = 4; -inline bool RGBDImage::has_step1() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void RGBDImage::set_has_step1() { - _has_bits_[0] |= 0x00000008u; -} -inline void RGBDImage::clear_has_step1() { - _has_bits_[0] &= ~0x00000008u; -} -inline void RGBDImage::clear_step1() { - step1_ = 0u; - clear_has_step1(); -} -inline ::google::protobuf::uint32 RGBDImage::step1() const { - return step1_; -} -inline void RGBDImage::set_step1(::google::protobuf::uint32 value) { - set_has_step1(); - step1_ = value; -} - -// required uint32 type1 = 5; -inline bool RGBDImage::has_type1() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void RGBDImage::set_has_type1() { - _has_bits_[0] |= 0x00000010u; -} -inline void RGBDImage::clear_has_type1() { - _has_bits_[0] &= ~0x00000010u; -} -inline void RGBDImage::clear_type1() { - type1_ = 0u; - clear_has_type1(); -} -inline ::google::protobuf::uint32 RGBDImage::type1() const { - return type1_; -} -inline void RGBDImage::set_type1(::google::protobuf::uint32 value) { - set_has_type1(); - type1_ = value; -} - -// required bytes imageData1 = 6; -inline bool RGBDImage::has_imagedata1() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void RGBDImage::set_has_imagedata1() { - _has_bits_[0] |= 0x00000020u; -} -inline void RGBDImage::clear_has_imagedata1() { - _has_bits_[0] &= ~0x00000020u; -} -inline void RGBDImage::clear_imagedata1() { - if (imagedata1_ != &::google::protobuf::internal::kEmptyString) { - imagedata1_->clear(); - } - clear_has_imagedata1(); -} -inline const ::std::string& RGBDImage::imagedata1() const { - return *imagedata1_; -} -inline void RGBDImage::set_imagedata1(const ::std::string& value) { - set_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - imagedata1_ = new ::std::string; - } - imagedata1_->assign(value); -} -inline void RGBDImage::set_imagedata1(const char* value) { - set_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - imagedata1_ = new ::std::string; - } - imagedata1_->assign(value); -} -inline void RGBDImage::set_imagedata1(const void* value, size_t size) { - set_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - imagedata1_ = new ::std::string; - } - imagedata1_->assign(reinterpret_cast(value), size); -} -inline ::std::string* RGBDImage::mutable_imagedata1() { - set_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - imagedata1_ = new ::std::string; - } - return imagedata1_; -} -inline ::std::string* RGBDImage::release_imagedata1() { - clear_has_imagedata1(); - if (imagedata1_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = imagedata1_; - imagedata1_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// required uint32 step2 = 7; -inline bool RGBDImage::has_step2() const { - return (_has_bits_[0] & 0x00000040u) != 0; -} -inline void RGBDImage::set_has_step2() { - _has_bits_[0] |= 0x00000040u; -} -inline void RGBDImage::clear_has_step2() { - _has_bits_[0] &= ~0x00000040u; -} -inline void RGBDImage::clear_step2() { - step2_ = 0u; - clear_has_step2(); -} -inline ::google::protobuf::uint32 RGBDImage::step2() const { - return step2_; -} -inline void RGBDImage::set_step2(::google::protobuf::uint32 value) { - set_has_step2(); - step2_ = value; -} - -// required uint32 type2 = 8; -inline bool RGBDImage::has_type2() const { - return (_has_bits_[0] & 0x00000080u) != 0; -} -inline void RGBDImage::set_has_type2() { - _has_bits_[0] |= 0x00000080u; -} -inline void RGBDImage::clear_has_type2() { - _has_bits_[0] &= ~0x00000080u; -} -inline void RGBDImage::clear_type2() { - type2_ = 0u; - clear_has_type2(); -} -inline ::google::protobuf::uint32 RGBDImage::type2() const { - return type2_; -} -inline void RGBDImage::set_type2(::google::protobuf::uint32 value) { - set_has_type2(); - type2_ = value; -} - -// required bytes imageData2 = 9; -inline bool RGBDImage::has_imagedata2() const { - return (_has_bits_[0] & 0x00000100u) != 0; -} -inline void RGBDImage::set_has_imagedata2() { - _has_bits_[0] |= 0x00000100u; -} -inline void RGBDImage::clear_has_imagedata2() { - _has_bits_[0] &= ~0x00000100u; -} -inline void RGBDImage::clear_imagedata2() { - if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { - imagedata2_->clear(); - } - clear_has_imagedata2(); -} -inline const ::std::string& RGBDImage::imagedata2() const { - return *imagedata2_; -} -inline void RGBDImage::set_imagedata2(const ::std::string& value) { - set_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - imagedata2_ = new ::std::string; - } - imagedata2_->assign(value); -} -inline void RGBDImage::set_imagedata2(const char* value) { - set_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - imagedata2_ = new ::std::string; - } - imagedata2_->assign(value); -} -inline void RGBDImage::set_imagedata2(const void* value, size_t size) { - set_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - imagedata2_ = new ::std::string; - } - imagedata2_->assign(reinterpret_cast(value), size); -} -inline ::std::string* RGBDImage::mutable_imagedata2() { - set_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - imagedata2_ = new ::std::string; - } - return imagedata2_; -} -inline ::std::string* RGBDImage::release_imagedata2() { - clear_has_imagedata2(); - if (imagedata2_ == &::google::protobuf::internal::kEmptyString) { - return NULL; - } else { - ::std::string* temp = imagedata2_; - imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - return temp; - } -} - -// optional uint32 camera_config = 10; -inline bool RGBDImage::has_camera_config() const { - return (_has_bits_[0] & 0x00000200u) != 0; -} -inline void RGBDImage::set_has_camera_config() { - _has_bits_[0] |= 0x00000200u; -} -inline void RGBDImage::clear_has_camera_config() { - _has_bits_[0] &= ~0x00000200u; -} -inline void RGBDImage::clear_camera_config() { - camera_config_ = 0u; - clear_has_camera_config(); -} -inline ::google::protobuf::uint32 RGBDImage::camera_config() const { - return camera_config_; -} -inline void RGBDImage::set_camera_config(::google::protobuf::uint32 value) { - set_has_camera_config(); - camera_config_ = value; -} - -// optional uint32 camera_type = 11; -inline bool RGBDImage::has_camera_type() const { - return (_has_bits_[0] & 0x00000400u) != 0; -} -inline void RGBDImage::set_has_camera_type() { - _has_bits_[0] |= 0x00000400u; -} -inline void RGBDImage::clear_has_camera_type() { - _has_bits_[0] &= ~0x00000400u; -} -inline void RGBDImage::clear_camera_type() { - camera_type_ = 0u; - clear_has_camera_type(); -} -inline ::google::protobuf::uint32 RGBDImage::camera_type() const { - return camera_type_; -} -inline void RGBDImage::set_camera_type(::google::protobuf::uint32 value) { - set_has_camera_type(); - camera_type_ = value; -} - -// optional float roll = 12; -inline bool RGBDImage::has_roll() const { - return (_has_bits_[0] & 0x00000800u) != 0; -} -inline void RGBDImage::set_has_roll() { - _has_bits_[0] |= 0x00000800u; -} -inline void RGBDImage::clear_has_roll() { - _has_bits_[0] &= ~0x00000800u; -} -inline void RGBDImage::clear_roll() { - roll_ = 0; - clear_has_roll(); -} -inline float RGBDImage::roll() const { - return roll_; -} -inline void RGBDImage::set_roll(float value) { - set_has_roll(); - roll_ = value; -} - -// optional float pitch = 13; -inline bool RGBDImage::has_pitch() const { - return (_has_bits_[0] & 0x00001000u) != 0; -} -inline void RGBDImage::set_has_pitch() { - _has_bits_[0] |= 0x00001000u; -} -inline void RGBDImage::clear_has_pitch() { - _has_bits_[0] &= ~0x00001000u; -} -inline void RGBDImage::clear_pitch() { - pitch_ = 0; - clear_has_pitch(); -} -inline float RGBDImage::pitch() const { - return pitch_; -} -inline void RGBDImage::set_pitch(float value) { - set_has_pitch(); - pitch_ = value; -} - -// optional float yaw = 14; -inline bool RGBDImage::has_yaw() const { - return (_has_bits_[0] & 0x00002000u) != 0; -} -inline void RGBDImage::set_has_yaw() { - _has_bits_[0] |= 0x00002000u; -} -inline void RGBDImage::clear_has_yaw() { - _has_bits_[0] &= ~0x00002000u; -} -inline void RGBDImage::clear_yaw() { - yaw_ = 0; - clear_has_yaw(); -} -inline float RGBDImage::yaw() const { - return yaw_; -} -inline void RGBDImage::set_yaw(float value) { - set_has_yaw(); - yaw_ = value; -} - -// optional float lon = 15; -inline bool RGBDImage::has_lon() const { - return (_has_bits_[0] & 0x00004000u) != 0; -} -inline void RGBDImage::set_has_lon() { - _has_bits_[0] |= 0x00004000u; -} -inline void RGBDImage::clear_has_lon() { - _has_bits_[0] &= ~0x00004000u; -} -inline void RGBDImage::clear_lon() { - lon_ = 0; - clear_has_lon(); -} -inline float RGBDImage::lon() const { - return lon_; -} -inline void RGBDImage::set_lon(float value) { - set_has_lon(); - lon_ = value; -} - -// optional float lat = 16; -inline bool RGBDImage::has_lat() const { - return (_has_bits_[0] & 0x00008000u) != 0; -} -inline void RGBDImage::set_has_lat() { - _has_bits_[0] |= 0x00008000u; -} -inline void RGBDImage::clear_has_lat() { - _has_bits_[0] &= ~0x00008000u; -} -inline void RGBDImage::clear_lat() { - lat_ = 0; - clear_has_lat(); -} -inline float RGBDImage::lat() const { - return lat_; -} -inline void RGBDImage::set_lat(float value) { - set_has_lat(); - lat_ = value; -} - -// optional float alt = 17; -inline bool RGBDImage::has_alt() const { - return (_has_bits_[0] & 0x00010000u) != 0; -} -inline void RGBDImage::set_has_alt() { - _has_bits_[0] |= 0x00010000u; -} -inline void RGBDImage::clear_has_alt() { - _has_bits_[0] &= ~0x00010000u; -} -inline void RGBDImage::clear_alt() { - alt_ = 0; - clear_has_alt(); -} -inline float RGBDImage::alt() const { - return alt_; -} -inline void RGBDImage::set_alt(float value) { - set_has_alt(); - alt_ = value; -} - -// optional float ground_x = 18; -inline bool RGBDImage::has_ground_x() const { - return (_has_bits_[0] & 0x00020000u) != 0; -} -inline void RGBDImage::set_has_ground_x() { - _has_bits_[0] |= 0x00020000u; -} -inline void RGBDImage::clear_has_ground_x() { - _has_bits_[0] &= ~0x00020000u; -} -inline void RGBDImage::clear_ground_x() { - ground_x_ = 0; - clear_has_ground_x(); -} -inline float RGBDImage::ground_x() const { - return ground_x_; -} -inline void RGBDImage::set_ground_x(float value) { - set_has_ground_x(); - ground_x_ = value; -} - -// optional float ground_y = 19; -inline bool RGBDImage::has_ground_y() const { - return (_has_bits_[0] & 0x00040000u) != 0; -} -inline void RGBDImage::set_has_ground_y() { - _has_bits_[0] |= 0x00040000u; -} -inline void RGBDImage::clear_has_ground_y() { - _has_bits_[0] &= ~0x00040000u; -} -inline void RGBDImage::clear_ground_y() { - ground_y_ = 0; - clear_has_ground_y(); -} -inline float RGBDImage::ground_y() const { - return ground_y_; -} -inline void RGBDImage::set_ground_y(float value) { - set_has_ground_y(); - ground_y_ = value; -} - -// optional float ground_z = 20; -inline bool RGBDImage::has_ground_z() const { - return (_has_bits_[0] & 0x00080000u) != 0; -} -inline void RGBDImage::set_has_ground_z() { - _has_bits_[0] |= 0x00080000u; -} -inline void RGBDImage::clear_has_ground_z() { - _has_bits_[0] &= ~0x00080000u; -} -inline void RGBDImage::clear_ground_z() { - ground_z_ = 0; - clear_has_ground_z(); -} -inline float RGBDImage::ground_z() const { - return ground_z_; -} -inline void RGBDImage::set_ground_z(float value) { - set_has_ground_z(); - ground_z_ = value; -} - -// repeated float camera_matrix = 21; -inline int RGBDImage::camera_matrix_size() const { - return camera_matrix_.size(); -} -inline void RGBDImage::clear_camera_matrix() { - camera_matrix_.Clear(); -} -inline float RGBDImage::camera_matrix(int index) const { - return camera_matrix_.Get(index); -} -inline void RGBDImage::set_camera_matrix(int index, float value) { - camera_matrix_.Set(index, value); -} -inline void RGBDImage::add_camera_matrix(float value) { - camera_matrix_.Add(value); -} -inline const ::google::protobuf::RepeatedField< float >& -RGBDImage::camera_matrix() const { - return camera_matrix_; -} -inline ::google::protobuf::RepeatedField< float >* -RGBDImage::mutable_camera_matrix() { - return &camera_matrix_; -} - -// ------------------------------------------------------------------- - -// Waypoint - -// required double x = 1; -inline bool Waypoint::has_x() const { - return (_has_bits_[0] & 0x00000001u) != 0; -} -inline void Waypoint::set_has_x() { - _has_bits_[0] |= 0x00000001u; -} -inline void Waypoint::clear_has_x() { - _has_bits_[0] &= ~0x00000001u; -} -inline void Waypoint::clear_x() { - x_ = 0; - clear_has_x(); -} -inline double Waypoint::x() const { - return x_; -} -inline void Waypoint::set_x(double value) { - set_has_x(); - x_ = value; -} - -// required double y = 2; -inline bool Waypoint::has_y() const { - return (_has_bits_[0] & 0x00000002u) != 0; -} -inline void Waypoint::set_has_y() { - _has_bits_[0] |= 0x00000002u; -} -inline void Waypoint::clear_has_y() { - _has_bits_[0] &= ~0x00000002u; -} -inline void Waypoint::clear_y() { - y_ = 0; - clear_has_y(); -} -inline double Waypoint::y() const { - return y_; -} -inline void Waypoint::set_y(double value) { - set_has_y(); - y_ = value; -} - -// optional double z = 3; -inline bool Waypoint::has_z() const { - return (_has_bits_[0] & 0x00000004u) != 0; -} -inline void Waypoint::set_has_z() { - _has_bits_[0] |= 0x00000004u; -} -inline void Waypoint::clear_has_z() { - _has_bits_[0] &= ~0x00000004u; -} -inline void Waypoint::clear_z() { - z_ = 0; - clear_has_z(); -} -inline double Waypoint::z() const { - return z_; -} -inline void Waypoint::set_z(double value) { - set_has_z(); - z_ = value; -} - -// optional double roll = 4; -inline bool Waypoint::has_roll() const { - return (_has_bits_[0] & 0x00000008u) != 0; -} -inline void Waypoint::set_has_roll() { - _has_bits_[0] |= 0x00000008u; -} -inline void Waypoint::clear_has_roll() { - _has_bits_[0] &= ~0x00000008u; -} -inline void Waypoint::clear_roll() { - roll_ = 0; - clear_has_roll(); -} -inline double Waypoint::roll() const { - return roll_; -} -inline void Waypoint::set_roll(double value) { - set_has_roll(); - roll_ = value; -} - -// optional double pitch = 5; -inline bool Waypoint::has_pitch() const { - return (_has_bits_[0] & 0x00000010u) != 0; -} -inline void Waypoint::set_has_pitch() { - _has_bits_[0] |= 0x00000010u; -} -inline void Waypoint::clear_has_pitch() { - _has_bits_[0] &= ~0x00000010u; -} -inline void Waypoint::clear_pitch() { - pitch_ = 0; - clear_has_pitch(); -} -inline double Waypoint::pitch() const { - return pitch_; -} -inline void Waypoint::set_pitch(double value) { - set_has_pitch(); - pitch_ = value; -} - -// optional double yaw = 6; -inline bool Waypoint::has_yaw() const { - return (_has_bits_[0] & 0x00000020u) != 0; -} -inline void Waypoint::set_has_yaw() { - _has_bits_[0] |= 0x00000020u; -} -inline void Waypoint::clear_has_yaw() { - _has_bits_[0] &= ~0x00000020u; -} -inline void Waypoint::clear_yaw() { - yaw_ = 0; - clear_has_yaw(); -} -inline double Waypoint::yaw() const { - return yaw_; -} -inline void Waypoint::set_yaw(double value) { - set_has_yaw(); - yaw_ = value; -} - - -// @@protoc_insertion_point(namespace_scope) - -} // namespace px - -#ifndef SWIG -namespace google { -namespace protobuf { - -template <> -inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_CoordinateFrameType>() { - return ::px::GLOverlay_CoordinateFrameType_descriptor(); -} -template <> -inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_Mode>() { - return ::px::GLOverlay_Mode_descriptor(); -} -template <> -inline const EnumDescriptor* GetEnumDescriptor< ::px::GLOverlay_Identifier>() { - return ::px::GLOverlay_Identifier_descriptor(); -} - -} // namespace google -} // namespace protobuf -#endif // SWIG - -// @@protoc_insertion_point(global_scope) - -#endif // PROTOBUF_pixhawk_2eproto__INCLUDED diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h deleted file mode 100644 index 7b3e3c0bd..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/protocol.h +++ /dev/null @@ -1,322 +0,0 @@ -#ifndef _MAVLINK_PROTOCOL_H_ -#define _MAVLINK_PROTOCOL_H_ - -#include "string.h" -#include "mavlink_types.h" - -/* - If you want MAVLink on a system that is native big-endian, - you need to define NATIVE_BIG_ENDIAN -*/ -#ifdef NATIVE_BIG_ENDIAN -# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN) -#else -# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN) -#endif - -#ifndef MAVLINK_STACK_BUFFER -#define MAVLINK_STACK_BUFFER 0 -#endif - -#ifndef MAVLINK_AVOID_GCC_STACK_BUG -# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__) -#endif - -#ifndef MAVLINK_ASSERT -#define MAVLINK_ASSERT(x) -#endif - -#ifndef MAVLINK_START_UART_SEND -#define MAVLINK_START_UART_SEND(chan, length) -#endif - -#ifndef MAVLINK_END_UART_SEND -#define MAVLINK_END_UART_SEND(chan, length) -#endif - -#ifdef MAVLINK_SEPARATE_HELPERS -#define MAVLINK_HELPER -#else -#define MAVLINK_HELPER static inline -#include "mavlink_helpers.h" -#endif // MAVLINK_SEPARATE_HELPERS - -/* always include the prototypes to ensure we don't get out of sync */ -MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan); -#if MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length, uint8_t crc_extra); -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length, uint8_t crc_extra); -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, - uint8_t length, uint8_t crc_extra); -#endif -#else -MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t chan, uint8_t length); -MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id, - uint8_t length); -MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length); -#endif // MAVLINK_CRC_EXTRA -MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg); -MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg); -MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c); -MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status); -MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, - uint8_t* r_bit_index, uint8_t* buffer); -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS -MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len); -#endif - -/** - * @brief Get the required buffer size for this message - */ -static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg) -{ - return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; -} - -#if MAVLINK_NEED_BYTE_SWAP -static inline void byte_swap_2(char *dst, const char *src) -{ - dst[0] = src[1]; - dst[1] = src[0]; -} -static inline void byte_swap_4(char *dst, const char *src) -{ - dst[0] = src[3]; - dst[1] = src[2]; - dst[2] = src[1]; - dst[3] = src[0]; -} -static inline void byte_swap_8(char *dst, const char *src) -{ - dst[0] = src[7]; - dst[1] = src[6]; - dst[2] = src[5]; - dst[3] = src[4]; - dst[4] = src[3]; - dst[5] = src[2]; - dst[6] = src[1]; - dst[7] = src[0]; -} -#elif !MAVLINK_ALIGNED_FIELDS -static inline void byte_copy_2(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; -} -static inline void byte_copy_4(char *dst, const char *src) -{ - dst[0] = src[0]; - dst[1] = src[1]; - dst[2] = src[2]; - dst[3] = src[3]; -} -static inline void byte_copy_8(char *dst, const char *src) -{ - memcpy(dst, src, 8); -} -#endif - -#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b -#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b -#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b - -#if MAVLINK_NEED_BYTE_SWAP -#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b) -#elif !MAVLINK_ALIGNED_FIELDS -#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b) -#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b) -#else -#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b -#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b -#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b -#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b -#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b -#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b -#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b -#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b -#endif - -/* - like memcpy(), but if src is NULL, do a memset to zero -*/ -static void mav_array_memcpy(void *dest, const void *src, size_t n) -{ - if (src == NULL) { - memset(dest, 0, n); - } else { - memcpy(dest, src, n); - } -} - -/* - * Place a char array into a buffer - */ -static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a uint8_t array into a buffer - */ -static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -/* - * Place a int8_t array into a buffer - */ -static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length) -{ - mav_array_memcpy(&buf[wire_offset], b, array_length); - -} - -#if MAVLINK_NEED_BYTE_SWAP -#define _MAV_PUT_ARRAY(TYPE, V) \ -static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \ -{ \ - if (b == NULL) { \ - memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \ - } else { \ - uint16_t i; \ - for (i=0; imsgid = MAVLINK_MSG_ID_TEST_TYPES; - return mavlink_finalize_message(msg, system_id, component_id, 179, 103); -} - -/** - * @brief Pack a test_types message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message was sent over - * @param msg The MAVLink message to compress the data into - * @param c char - * @param s string - * @param u8 uint8_t - * @param u16 uint16_t - * @param u32 uint32_t - * @param u64 uint64_t - * @param s8 int8_t - * @param s16 int16_t - * @param s32 int32_t - * @param s64 int64_t - * @param f float - * @param d double - * @param u8_array uint8_t_array - * @param u16_array uint16_t_array - * @param u32_array uint32_t_array - * @param u64_array uint64_t_array - * @param s8_array int8_t_array - * @param s16_array int16_t_array - * @param s32_array int32_t_array - * @param s64_array int64_t_array - * @param f_array float_array - * @param d_array double_array - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_test_types_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - char c,const char *s,uint8_t u8,uint16_t u16,uint32_t u32,uint64_t u64,int8_t s8,int16_t s16,int32_t s32,int64_t s64,float f,double d,const uint8_t *u8_array,const uint16_t *u16_array,const uint32_t *u32_array,const uint64_t *u64_array,const int8_t *s8_array,const int16_t *s16_array,const int32_t *s32_array,const int64_t *s64_array,const float *f_array,const double *d_array) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[179]; - _mav_put_uint64_t(buf, 0, u64); - _mav_put_int64_t(buf, 8, s64); - _mav_put_double(buf, 16, d); - _mav_put_uint32_t(buf, 96, u32); - _mav_put_int32_t(buf, 100, s32); - _mav_put_float(buf, 104, f); - _mav_put_uint16_t(buf, 144, u16); - _mav_put_int16_t(buf, 146, s16); - _mav_put_char(buf, 160, c); - _mav_put_uint8_t(buf, 171, u8); - _mav_put_int8_t(buf, 172, s8); - _mav_put_uint64_t_array(buf, 24, u64_array, 3); - _mav_put_int64_t_array(buf, 48, s64_array, 3); - _mav_put_double_array(buf, 72, d_array, 3); - _mav_put_uint32_t_array(buf, 108, u32_array, 3); - _mav_put_int32_t_array(buf, 120, s32_array, 3); - _mav_put_float_array(buf, 132, f_array, 3); - _mav_put_uint16_t_array(buf, 148, u16_array, 3); - _mav_put_int16_t_array(buf, 154, s16_array, 3); - _mav_put_char_array(buf, 161, s, 10); - _mav_put_uint8_t_array(buf, 173, u8_array, 3); - _mav_put_int8_t_array(buf, 176, s8_array, 3); - memcpy(_MAV_PAYLOAD(msg), buf, 179); -#else - mavlink_test_types_t packet; - packet.u64 = u64; - packet.s64 = s64; - packet.d = d; - packet.u32 = u32; - packet.s32 = s32; - packet.f = f; - packet.u16 = u16; - packet.s16 = s16; - packet.c = c; - packet.u8 = u8; - packet.s8 = s8; - mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); - mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); - mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); - mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); - mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); - mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); - mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); - mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); - mav_array_memcpy(packet.s, s, sizeof(char)*10); - mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); - mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); - memcpy(_MAV_PAYLOAD(msg), &packet, 179); -#endif - - msg->msgid = MAVLINK_MSG_ID_TEST_TYPES; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 179, 103); -} - -/** - * @brief Encode a test_types struct into a message - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param test_types C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_test_types_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_test_types_t* test_types) -{ - return mavlink_msg_test_types_pack(system_id, component_id, msg, test_types->c, test_types->s, test_types->u8, test_types->u16, test_types->u32, test_types->u64, test_types->s8, test_types->s16, test_types->s32, test_types->s64, test_types->f, test_types->d, test_types->u8_array, test_types->u16_array, test_types->u32_array, test_types->u64_array, test_types->s8_array, test_types->s16_array, test_types->s32_array, test_types->s64_array, test_types->f_array, test_types->d_array); -} - -/** - * @brief Send a test_types message - * @param chan MAVLink channel to send the message - * - * @param c char - * @param s string - * @param u8 uint8_t - * @param u16 uint16_t - * @param u32 uint32_t - * @param u64 uint64_t - * @param s8 int8_t - * @param s16 int16_t - * @param s32 int32_t - * @param s64 int64_t - * @param f float - * @param d double - * @param u8_array uint8_t_array - * @param u16_array uint16_t_array - * @param u32_array uint32_t_array - * @param u64_array uint64_t_array - * @param s8_array int8_t_array - * @param s16_array int16_t_array - * @param s32_array int32_t_array - * @param s64_array int64_t_array - * @param f_array float_array - * @param d_array double_array - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_test_types_send(mavlink_channel_t chan, char c, const char *s, uint8_t u8, uint16_t u16, uint32_t u32, uint64_t u64, int8_t s8, int16_t s16, int32_t s32, int64_t s64, float f, double d, const uint8_t *u8_array, const uint16_t *u16_array, const uint32_t *u32_array, const uint64_t *u64_array, const int8_t *s8_array, const int16_t *s16_array, const int32_t *s32_array, const int64_t *s64_array, const float *f_array, const double *d_array) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[179]; - _mav_put_uint64_t(buf, 0, u64); - _mav_put_int64_t(buf, 8, s64); - _mav_put_double(buf, 16, d); - _mav_put_uint32_t(buf, 96, u32); - _mav_put_int32_t(buf, 100, s32); - _mav_put_float(buf, 104, f); - _mav_put_uint16_t(buf, 144, u16); - _mav_put_int16_t(buf, 146, s16); - _mav_put_char(buf, 160, c); - _mav_put_uint8_t(buf, 171, u8); - _mav_put_int8_t(buf, 172, s8); - _mav_put_uint64_t_array(buf, 24, u64_array, 3); - _mav_put_int64_t_array(buf, 48, s64_array, 3); - _mav_put_double_array(buf, 72, d_array, 3); - _mav_put_uint32_t_array(buf, 108, u32_array, 3); - _mav_put_int32_t_array(buf, 120, s32_array, 3); - _mav_put_float_array(buf, 132, f_array, 3); - _mav_put_uint16_t_array(buf, 148, u16_array, 3); - _mav_put_int16_t_array(buf, 154, s16_array, 3); - _mav_put_char_array(buf, 161, s, 10); - _mav_put_uint8_t_array(buf, 173, u8_array, 3); - _mav_put_int8_t_array(buf, 176, s8_array, 3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, buf, 179, 103); -#else - mavlink_test_types_t packet; - packet.u64 = u64; - packet.s64 = s64; - packet.d = d; - packet.u32 = u32; - packet.s32 = s32; - packet.f = f; - packet.u16 = u16; - packet.s16 = s16; - packet.c = c; - packet.u8 = u8; - packet.s8 = s8; - mav_array_memcpy(packet.u64_array, u64_array, sizeof(uint64_t)*3); - mav_array_memcpy(packet.s64_array, s64_array, sizeof(int64_t)*3); - mav_array_memcpy(packet.d_array, d_array, sizeof(double)*3); - mav_array_memcpy(packet.u32_array, u32_array, sizeof(uint32_t)*3); - mav_array_memcpy(packet.s32_array, s32_array, sizeof(int32_t)*3); - mav_array_memcpy(packet.f_array, f_array, sizeof(float)*3); - mav_array_memcpy(packet.u16_array, u16_array, sizeof(uint16_t)*3); - mav_array_memcpy(packet.s16_array, s16_array, sizeof(int16_t)*3); - mav_array_memcpy(packet.s, s, sizeof(char)*10); - mav_array_memcpy(packet.u8_array, u8_array, sizeof(uint8_t)*3); - mav_array_memcpy(packet.s8_array, s8_array, sizeof(int8_t)*3); - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_TEST_TYPES, (const char *)&packet, 179, 103); -#endif -} - -#endif - -// MESSAGE TEST_TYPES UNPACKING - - -/** - * @brief Get field c from test_types message - * - * @return char - */ -static inline char mavlink_msg_test_types_get_c(const mavlink_message_t* msg) -{ - return _MAV_RETURN_char(msg, 160); -} - -/** - * @brief Get field s from test_types message - * - * @return string - */ -static inline uint16_t mavlink_msg_test_types_get_s(const mavlink_message_t* msg, char *s) -{ - return _MAV_RETURN_char_array(msg, s, 10, 161); -} - -/** - * @brief Get field u8 from test_types message - * - * @return uint8_t - */ -static inline uint8_t mavlink_msg_test_types_get_u8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint8_t(msg, 171); -} - -/** - * @brief Get field u16 from test_types message - * - * @return uint16_t - */ -static inline uint16_t mavlink_msg_test_types_get_u16(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint16_t(msg, 144); -} - -/** - * @brief Get field u32 from test_types message - * - * @return uint32_t - */ -static inline uint32_t mavlink_msg_test_types_get_u32(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint32_t(msg, 96); -} - -/** - * @brief Get field u64 from test_types message - * - * @return uint64_t - */ -static inline uint64_t mavlink_msg_test_types_get_u64(const mavlink_message_t* msg) -{ - return _MAV_RETURN_uint64_t(msg, 0); -} - -/** - * @brief Get field s8 from test_types message - * - * @return int8_t - */ -static inline int8_t mavlink_msg_test_types_get_s8(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int8_t(msg, 172); -} - -/** - * @brief Get field s16 from test_types message - * - * @return int16_t - */ -static inline int16_t mavlink_msg_test_types_get_s16(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int16_t(msg, 146); -} - -/** - * @brief Get field s32 from test_types message - * - * @return int32_t - */ -static inline int32_t mavlink_msg_test_types_get_s32(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int32_t(msg, 100); -} - -/** - * @brief Get field s64 from test_types message - * - * @return int64_t - */ -static inline int64_t mavlink_msg_test_types_get_s64(const mavlink_message_t* msg) -{ - return _MAV_RETURN_int64_t(msg, 8); -} - -/** - * @brief Get field f from test_types message - * - * @return float - */ -static inline float mavlink_msg_test_types_get_f(const mavlink_message_t* msg) -{ - return _MAV_RETURN_float(msg, 104); -} - -/** - * @brief Get field d from test_types message - * - * @return double - */ -static inline double mavlink_msg_test_types_get_d(const mavlink_message_t* msg) -{ - return _MAV_RETURN_double(msg, 16); -} - -/** - * @brief Get field u8_array from test_types message - * - * @return uint8_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u8_array(const mavlink_message_t* msg, uint8_t *u8_array) -{ - return _MAV_RETURN_uint8_t_array(msg, u8_array, 3, 173); -} - -/** - * @brief Get field u16_array from test_types message - * - * @return uint16_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u16_array(const mavlink_message_t* msg, uint16_t *u16_array) -{ - return _MAV_RETURN_uint16_t_array(msg, u16_array, 3, 148); -} - -/** - * @brief Get field u32_array from test_types message - * - * @return uint32_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u32_array(const mavlink_message_t* msg, uint32_t *u32_array) -{ - return _MAV_RETURN_uint32_t_array(msg, u32_array, 3, 108); -} - -/** - * @brief Get field u64_array from test_types message - * - * @return uint64_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_u64_array(const mavlink_message_t* msg, uint64_t *u64_array) -{ - return _MAV_RETURN_uint64_t_array(msg, u64_array, 3, 24); -} - -/** - * @brief Get field s8_array from test_types message - * - * @return int8_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s8_array(const mavlink_message_t* msg, int8_t *s8_array) -{ - return _MAV_RETURN_int8_t_array(msg, s8_array, 3, 176); -} - -/** - * @brief Get field s16_array from test_types message - * - * @return int16_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s16_array(const mavlink_message_t* msg, int16_t *s16_array) -{ - return _MAV_RETURN_int16_t_array(msg, s16_array, 3, 154); -} - -/** - * @brief Get field s32_array from test_types message - * - * @return int32_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s32_array(const mavlink_message_t* msg, int32_t *s32_array) -{ - return _MAV_RETURN_int32_t_array(msg, s32_array, 3, 120); -} - -/** - * @brief Get field s64_array from test_types message - * - * @return int64_t_array - */ -static inline uint16_t mavlink_msg_test_types_get_s64_array(const mavlink_message_t* msg, int64_t *s64_array) -{ - return _MAV_RETURN_int64_t_array(msg, s64_array, 3, 48); -} - -/** - * @brief Get field f_array from test_types message - * - * @return float_array - */ -static inline uint16_t mavlink_msg_test_types_get_f_array(const mavlink_message_t* msg, float *f_array) -{ - return _MAV_RETURN_float_array(msg, f_array, 3, 132); -} - -/** - * @brief Get field d_array from test_types message - * - * @return double_array - */ -static inline uint16_t mavlink_msg_test_types_get_d_array(const mavlink_message_t* msg, double *d_array) -{ - return _MAV_RETURN_double_array(msg, d_array, 3, 72); -} - -/** - * @brief Decode a test_types message into a struct - * - * @param msg The message to decode - * @param test_types C-struct to decode the message contents into - */ -static inline void mavlink_msg_test_types_decode(const mavlink_message_t* msg, mavlink_test_types_t* test_types) -{ -#if MAVLINK_NEED_BYTE_SWAP - test_types->u64 = mavlink_msg_test_types_get_u64(msg); - test_types->s64 = mavlink_msg_test_types_get_s64(msg); - test_types->d = mavlink_msg_test_types_get_d(msg); - mavlink_msg_test_types_get_u64_array(msg, test_types->u64_array); - mavlink_msg_test_types_get_s64_array(msg, test_types->s64_array); - mavlink_msg_test_types_get_d_array(msg, test_types->d_array); - test_types->u32 = mavlink_msg_test_types_get_u32(msg); - test_types->s32 = mavlink_msg_test_types_get_s32(msg); - test_types->f = mavlink_msg_test_types_get_f(msg); - mavlink_msg_test_types_get_u32_array(msg, test_types->u32_array); - mavlink_msg_test_types_get_s32_array(msg, test_types->s32_array); - mavlink_msg_test_types_get_f_array(msg, test_types->f_array); - test_types->u16 = mavlink_msg_test_types_get_u16(msg); - test_types->s16 = mavlink_msg_test_types_get_s16(msg); - mavlink_msg_test_types_get_u16_array(msg, test_types->u16_array); - mavlink_msg_test_types_get_s16_array(msg, test_types->s16_array); - test_types->c = mavlink_msg_test_types_get_c(msg); - mavlink_msg_test_types_get_s(msg, test_types->s); - test_types->u8 = mavlink_msg_test_types_get_u8(msg); - test_types->s8 = mavlink_msg_test_types_get_s8(msg); - mavlink_msg_test_types_get_u8_array(msg, test_types->u8_array); - mavlink_msg_test_types_get_s8_array(msg, test_types->s8_array); -#else - memcpy(test_types, _MAV_PAYLOAD(msg), 179); -#endif -} diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h deleted file mode 100644 index 4dc04f889..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/test.h +++ /dev/null @@ -1,53 +0,0 @@ -/** @file - * @brief MAVLink comm protocol generated from test.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef TEST_H -#define TEST_H - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {179, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {103, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0} -#endif - -#ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_TEST_TYPES, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}, {NULL}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_TEST - - - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION 3 -#endif - -// ENUM DEFINITIONS - - - -// MESSAGE DEFINITIONS -#include "./mavlink_msg_test_types.h" - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // TEST_H diff --git a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h b/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h deleted file mode 100644 index 658e1ae07..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/include_v1.0/test/testsuite.h +++ /dev/null @@ -1,120 +0,0 @@ -/** @file - * @brief MAVLink comm protocol testsuite generated from test.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef TEST_TESTSUITE_H -#define TEST_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL - -static void mavlink_test_test(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - - mavlink_test_test(system_id, component_id, last_msg); -} -#endif - - - - -static void mavlink_test_test_types(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_test_types_t packet_in = { - 93372036854775807ULL, - 93372036854776311LL, - 235.0, - { 93372036854777319, 93372036854777320, 93372036854777321 }, - { 93372036854778831, 93372036854778832, 93372036854778833 }, - { 627.0, 628.0, 629.0 }, - 963502456, - 963502664, - 745.0, - { 963503080, 963503081, 963503082 }, - { 963503704, 963503705, 963503706 }, - { 941.0, 942.0, 943.0 }, - 24723, - 24827, - { 24931, 24932, 24933 }, - { 25243, 25244, 25245 }, - 'E', - "FGHIJKLMN", - 198, - 9, - { 76, 77, 78 }, - { 21, 22, 23 }, - }; - mavlink_test_types_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - packet1.u64 = packet_in.u64; - packet1.s64 = packet_in.s64; - packet1.d = packet_in.d; - packet1.u32 = packet_in.u32; - packet1.s32 = packet_in.s32; - packet1.f = packet_in.f; - packet1.u16 = packet_in.u16; - packet1.s16 = packet_in.s16; - packet1.c = packet_in.c; - packet1.u8 = packet_in.u8; - packet1.s8 = packet_in.s8; - - mav_array_memcpy(packet1.u64_array, packet_in.u64_array, sizeof(uint64_t)*3); - mav_array_memcpy(packet1.s64_array, packet_in.s64_array, sizeof(int64_t)*3); - mav_array_memcpy(packet1.d_array, packet_in.d_array, sizeof(double)*3); - mav_array_memcpy(packet1.u32_array, packet_in.u32_array, sizeof(uint32_t)*3); - mav_array_memcpy(packet1.s32_array, packet_in.s32_array, sizeof(int32_t)*3); - mav_array_memcpy(packet1.f_array, packet_in.f_array, sizeof(float)*3); - mav_array_memcpy(packet1.u16_array, packet_in.u16_array, sizeof(uint16_t)*3); - mav_array_memcpy(packet1.s16_array, packet_in.s16_array, sizeof(int16_t)*3); - mav_array_memcpy(packet1.s, packet_in.s, sizeof(char)*10); - mav_array_memcpy(packet1.u8_array, packet_in.u8_array, sizeof(uint8_t)*3); - mav_array_memcpy(packet1.s8_array, packet_in.s8_array, sizeof(int8_t)*3); - - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_test_types_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_test_types_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_test_types_pack(system_id, component_id, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); - mavlink_msg_test_types_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_test_types_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.c , packet1.s , packet1.u8 , packet1.u16 , packet1.u32 , packet1.u64 , packet1.s8 , packet1.s16 , packet1.s32 , packet1.s64 , packet1.f , packet1.d , packet1.u8_array , packet1.u16_array , packet1.u32_array , packet1.u64_array , packet1.s8_array , packet1.s16_array , packet1.s32_array , packet1.s64_array , packet1.f_array , packet1.d_array ); - mavlink_msg_test_types_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; i - -#include -#include -#include -#include -#include -#include -// @@protoc_insertion_point(includes) - -namespace px { - -namespace { - -const ::google::protobuf::Descriptor* HeaderInfo_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - HeaderInfo_reflection_ = NULL; -const ::google::protobuf::Descriptor* GLOverlay_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - GLOverlay_reflection_ = NULL; -const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor_ = NULL; -const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor_ = NULL; -const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor_ = NULL; -const ::google::protobuf::Descriptor* Obstacle_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - Obstacle_reflection_ = NULL; -const ::google::protobuf::Descriptor* ObstacleList_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - ObstacleList_reflection_ = NULL; -const ::google::protobuf::Descriptor* ObstacleMap_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - ObstacleMap_reflection_ = NULL; -const ::google::protobuf::Descriptor* Path_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - Path_reflection_ = NULL; -const ::google::protobuf::Descriptor* PointCloudXYZI_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - PointCloudXYZI_reflection_ = NULL; -const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - PointCloudXYZI_PointXYZI_reflection_ = NULL; -const ::google::protobuf::Descriptor* PointCloudXYZRGB_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - PointCloudXYZRGB_reflection_ = NULL; -const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - PointCloudXYZRGB_PointXYZRGB_reflection_ = NULL; -const ::google::protobuf::Descriptor* RGBDImage_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - RGBDImage_reflection_ = NULL; -const ::google::protobuf::Descriptor* Waypoint_descriptor_ = NULL; -const ::google::protobuf::internal::GeneratedMessageReflection* - Waypoint_reflection_ = NULL; - -} // namespace - - -void protobuf_AssignDesc_pixhawk_2eproto() { - protobuf_AddDesc_pixhawk_2eproto(); - const ::google::protobuf::FileDescriptor* file = - ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName( - "pixhawk.proto"); - GOOGLE_CHECK(file != NULL); - HeaderInfo_descriptor_ = file->message_type(0); - static const int HeaderInfo_offsets_[3] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_sysid_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, source_compid_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, timestamp_), - }; - HeaderInfo_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - HeaderInfo_descriptor_, - HeaderInfo::default_instance_, - HeaderInfo_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(HeaderInfo, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(HeaderInfo)); - GLOverlay_descriptor_ = file->message_type(1); - static const int GLOverlay_offsets_[7] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, name_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, coordinateframetype_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, origin_z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, data_), - }; - GLOverlay_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - GLOverlay_descriptor_, - GLOverlay::default_instance_, - GLOverlay_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(GLOverlay, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(GLOverlay)); - GLOverlay_CoordinateFrameType_descriptor_ = GLOverlay_descriptor_->enum_type(0); - GLOverlay_Mode_descriptor_ = GLOverlay_descriptor_->enum_type(1); - GLOverlay_Identifier_descriptor_ = GLOverlay_descriptor_->enum_type(2); - Obstacle_descriptor_ = file->message_type(2); - static const int Obstacle_offsets_[6] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, length_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, width_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, height_), - }; - Obstacle_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - Obstacle_descriptor_, - Obstacle::default_instance_, - Obstacle_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Obstacle, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(Obstacle)); - ObstacleList_descriptor_ = file->message_type(3); - static const int ObstacleList_offsets_[2] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, obstacles_), - }; - ObstacleList_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - ObstacleList_descriptor_, - ObstacleList::default_instance_, - ObstacleList_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleList, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(ObstacleList)); - ObstacleMap_descriptor_ = file->message_type(4); - static const int ObstacleMap_offsets_[10] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, type_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, resolution_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, rows_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, cols_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapr0_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, mapc0_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayr0_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, arrayc0_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, data_), - }; - ObstacleMap_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - ObstacleMap_descriptor_, - ObstacleMap::default_instance_, - ObstacleMap_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(ObstacleMap, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(ObstacleMap)); - Path_descriptor_ = file->message_type(5); - static const int Path_offsets_[2] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, waypoints_), - }; - Path_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - Path_descriptor_, - Path::default_instance_, - Path_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Path, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(Path)); - PointCloudXYZI_descriptor_ = file->message_type(6); - static const int PointCloudXYZI_offsets_[2] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, points_), - }; - PointCloudXYZI_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - PointCloudXYZI_descriptor_, - PointCloudXYZI::default_instance_, - PointCloudXYZI_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(PointCloudXYZI)); - PointCloudXYZI_PointXYZI_descriptor_ = PointCloudXYZI_descriptor_->nested_type(0); - static const int PointCloudXYZI_PointXYZI_offsets_[4] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, intensity_), - }; - PointCloudXYZI_PointXYZI_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - PointCloudXYZI_PointXYZI_descriptor_, - PointCloudXYZI_PointXYZI::default_instance_, - PointCloudXYZI_PointXYZI_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZI_PointXYZI, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(PointCloudXYZI_PointXYZI)); - PointCloudXYZRGB_descriptor_ = file->message_type(7); - static const int PointCloudXYZRGB_offsets_[2] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, points_), - }; - PointCloudXYZRGB_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - PointCloudXYZRGB_descriptor_, - PointCloudXYZRGB::default_instance_, - PointCloudXYZRGB_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(PointCloudXYZRGB)); - PointCloudXYZRGB_PointXYZRGB_descriptor_ = PointCloudXYZRGB_descriptor_->nested_type(0); - static const int PointCloudXYZRGB_PointXYZRGB_offsets_[4] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, rgb_), - }; - PointCloudXYZRGB_PointXYZRGB_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - PointCloudXYZRGB_PointXYZRGB_descriptor_, - PointCloudXYZRGB_PointXYZRGB::default_instance_, - PointCloudXYZRGB_PointXYZRGB_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(PointCloudXYZRGB_PointXYZRGB, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(PointCloudXYZRGB_PointXYZRGB)); - RGBDImage_descriptor_ = file->message_type(8); - static const int RGBDImage_offsets_[21] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, header_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, cols_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, rows_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step1_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type1_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata1_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, step2_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, type2_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, imagedata2_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_config_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_type_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, roll_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, pitch_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, yaw_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lon_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, lat_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, alt_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, ground_z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, camera_matrix_), - }; - RGBDImage_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - RGBDImage_descriptor_, - RGBDImage::default_instance_, - RGBDImage_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RGBDImage, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(RGBDImage)); - Waypoint_descriptor_ = file->message_type(9); - static const int Waypoint_offsets_[6] = { - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, x_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, y_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, z_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, roll_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, pitch_), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, yaw_), - }; - Waypoint_reflection_ = - new ::google::protobuf::internal::GeneratedMessageReflection( - Waypoint_descriptor_, - Waypoint::default_instance_, - Waypoint_offsets_, - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _has_bits_[0]), - GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Waypoint, _unknown_fields_), - -1, - ::google::protobuf::DescriptorPool::generated_pool(), - ::google::protobuf::MessageFactory::generated_factory(), - sizeof(Waypoint)); -} - -namespace { - -GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_); -inline void protobuf_AssignDescriptorsOnce() { - ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_, - &protobuf_AssignDesc_pixhawk_2eproto); -} - -void protobuf_RegisterTypes(const ::std::string&) { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - HeaderInfo_descriptor_, &HeaderInfo::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - GLOverlay_descriptor_, &GLOverlay::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - Obstacle_descriptor_, &Obstacle::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - ObstacleList_descriptor_, &ObstacleList::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - ObstacleMap_descriptor_, &ObstacleMap::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - Path_descriptor_, &Path::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - PointCloudXYZI_descriptor_, &PointCloudXYZI::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - PointCloudXYZI_PointXYZI_descriptor_, &PointCloudXYZI_PointXYZI::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - PointCloudXYZRGB_descriptor_, &PointCloudXYZRGB::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - PointCloudXYZRGB_PointXYZRGB_descriptor_, &PointCloudXYZRGB_PointXYZRGB::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - RGBDImage_descriptor_, &RGBDImage::default_instance()); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage( - Waypoint_descriptor_, &Waypoint::default_instance()); -} - -} // namespace - -void protobuf_ShutdownFile_pixhawk_2eproto() { - delete HeaderInfo::default_instance_; - delete HeaderInfo_reflection_; - delete GLOverlay::default_instance_; - delete GLOverlay_reflection_; - delete Obstacle::default_instance_; - delete Obstacle_reflection_; - delete ObstacleList::default_instance_; - delete ObstacleList_reflection_; - delete ObstacleMap::default_instance_; - delete ObstacleMap_reflection_; - delete Path::default_instance_; - delete Path_reflection_; - delete PointCloudXYZI::default_instance_; - delete PointCloudXYZI_reflection_; - delete PointCloudXYZI_PointXYZI::default_instance_; - delete PointCloudXYZI_PointXYZI_reflection_; - delete PointCloudXYZRGB::default_instance_; - delete PointCloudXYZRGB_reflection_; - delete PointCloudXYZRGB_PointXYZRGB::default_instance_; - delete PointCloudXYZRGB_PointXYZRGB_reflection_; - delete RGBDImage::default_instance_; - delete RGBDImage_reflection_; - delete Waypoint::default_instance_; - delete Waypoint_reflection_; -} - -void protobuf_AddDesc_pixhawk_2eproto() { - static bool already_here = false; - if (already_here) return; - already_here = true; - GOOGLE_PROTOBUF_VERIFY_VERSION; - - ::google::protobuf::DescriptorPool::InternalAddGeneratedFile( - "\n\rpixhawk.proto\022\002px\"L\n\nHeaderInfo\022\024\n\014sou" - "rce_sysid\030\001 \002(\005\022\025\n\rsource_compid\030\002 \002(\005\022\021" - "\n\ttimestamp\030\003 \002(\001\"\377\004\n\tGLOverlay\022\036\n\006heade" - "r\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004name\030\002 \001(\t\022>\n" - "\023coordinateFrameType\030\003 \001(\0162!.px.GLOverla" - "y.CoordinateFrameType\022\020\n\010origin_x\030\004 \001(\001\022" - "\020\n\010origin_y\030\005 \001(\001\022\020\n\010origin_z\030\006 \001(\001\022\014\n\004d" - "ata\030\007 \001(\014\",\n\023CoordinateFrameType\022\n\n\006GLOB" - "AL\020\000\022\t\n\005LOCAL\020\001\"\333\001\n\004Mode\022\n\n\006POINTS\020\000\022\t\n\005" - "LINES\020\001\022\016\n\nLINE_STRIP\020\002\022\r\n\tLINE_LOOP\020\003\022\r" - "\n\tTRIANGLES\020\004\022\022\n\016TRIANGLE_STRIP\020\005\022\020\n\014TRI" - "ANGLE_FAN\020\006\022\t\n\005QUADS\020\007\022\016\n\nQUAD_STRIP\020\010\022\013" - "\n\007POLYGON\020\t\022\020\n\014SOLID_CIRCLE\020\n\022\017\n\013WIRE_CI" - "RCLE\020\013\022\016\n\nSOLID_CUBE\020\014\022\r\n\tWIRE_CUBE\020\r\"\263\001" - "\n\nIdentifier\022\007\n\003END\020\016\022\014\n\010VERTEX2F\020\017\022\014\n\010V" - "ERTEX3F\020\020\022\013\n\007ROTATEF\020\021\022\016\n\nTRANSLATEF\020\022\022\n" - "\n\006SCALEF\020\023\022\017\n\013PUSH_MATRIX\020\024\022\016\n\nPOP_MATRI" - "X\020\025\022\013\n\007COLOR3F\020\026\022\013\n\007COLOR4F\020\027\022\r\n\tPOINTSI" - "ZE\020\030\022\r\n\tLINEWIDTH\020\031\"Z\n\010Obstacle\022\t\n\001x\030\001 \001" - "(\002\022\t\n\001y\030\002 \001(\002\022\t\n\001z\030\003 \001(\002\022\016\n\006length\030\004 \001(\002" - "\022\r\n\005width\030\005 \001(\002\022\016\n\006height\030\006 \001(\002\"O\n\014Obsta" - "cleList\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo\022" - "\037\n\tobstacles\030\002 \003(\0132\014.px.Obstacle\"\271\001\n\013Obs" - "tacleMap\022\036\n\006header\030\001 \002(\0132\016.px.HeaderInfo" - "\022\014\n\004type\030\002 \002(\005\022\022\n\nresolution\030\003 \001(\002\022\014\n\004ro" - "ws\030\004 \001(\005\022\014\n\004cols\030\005 \001(\005\022\r\n\005mapR0\030\006 \001(\005\022\r\n" - "\005mapC0\030\007 \001(\005\022\017\n\007arrayR0\030\010 \001(\005\022\017\n\007arrayC0" - "\030\t \001(\005\022\014\n\004data\030\n \001(\014\"G\n\004Path\022\036\n\006header\030\001" - " \002(\0132\016.px.HeaderInfo\022\037\n\twaypoints\030\002 \003(\0132" - "\014.px.Waypoint\"\237\001\n\016PointCloudXYZI\022\036\n\006head" - "er\030\001 \002(\0132\016.px.HeaderInfo\022,\n\006points\030\002 \003(\013" - "2\034.px.PointCloudXYZI.PointXYZI\032\?\n\tPointX" - "YZI\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z\030\003 \002(\002\022\021\n\t" - "intensity\030\004 \002(\002\"\241\001\n\020PointCloudXYZRGB\022\036\n\006" - "header\030\001 \002(\0132\016.px.HeaderInfo\0220\n\006points\030\002" - " \003(\0132 .px.PointCloudXYZRGB.PointXYZRGB\032;" - "\n\013PointXYZRGB\022\t\n\001x\030\001 \002(\002\022\t\n\001y\030\002 \002(\002\022\t\n\001z" - "\030\003 \002(\002\022\013\n\003rgb\030\004 \002(\002\"\365\002\n\tRGBDImage\022\036\n\006hea" - "der\030\001 \002(\0132\016.px.HeaderInfo\022\014\n\004cols\030\002 \002(\r\022" - "\014\n\004rows\030\003 \002(\r\022\r\n\005step1\030\004 \002(\r\022\r\n\005type1\030\005 " - "\002(\r\022\022\n\nimageData1\030\006 \002(\014\022\r\n\005step2\030\007 \002(\r\022\r" - "\n\005type2\030\010 \002(\r\022\022\n\nimageData2\030\t \002(\014\022\025\n\rcam" - "era_config\030\n \001(\r\022\023\n\013camera_type\030\013 \001(\r\022\014\n" - "\004roll\030\014 \001(\002\022\r\n\005pitch\030\r \001(\002\022\013\n\003yaw\030\016 \001(\002\022" - "\013\n\003lon\030\017 \001(\002\022\013\n\003lat\030\020 \001(\002\022\013\n\003alt\030\021 \001(\002\022\020" - "\n\010ground_x\030\022 \001(\002\022\020\n\010ground_y\030\023 \001(\002\022\020\n\010gr" - "ound_z\030\024 \001(\002\022\025\n\rcamera_matrix\030\025 \003(\002\"U\n\010W" - "aypoint\022\t\n\001x\030\001 \002(\001\022\t\n\001y\030\002 \002(\001\022\t\n\001z\030\003 \001(\001" - "\022\014\n\004roll\030\004 \001(\001\022\r\n\005pitch\030\005 \001(\001\022\013\n\003yaw\030\006 \001" - "(\001", 1962); - ::google::protobuf::MessageFactory::InternalRegisterGeneratedFile( - "pixhawk.proto", &protobuf_RegisterTypes); - HeaderInfo::default_instance_ = new HeaderInfo(); - GLOverlay::default_instance_ = new GLOverlay(); - Obstacle::default_instance_ = new Obstacle(); - ObstacleList::default_instance_ = new ObstacleList(); - ObstacleMap::default_instance_ = new ObstacleMap(); - Path::default_instance_ = new Path(); - PointCloudXYZI::default_instance_ = new PointCloudXYZI(); - PointCloudXYZI_PointXYZI::default_instance_ = new PointCloudXYZI_PointXYZI(); - PointCloudXYZRGB::default_instance_ = new PointCloudXYZRGB(); - PointCloudXYZRGB_PointXYZRGB::default_instance_ = new PointCloudXYZRGB_PointXYZRGB(); - RGBDImage::default_instance_ = new RGBDImage(); - Waypoint::default_instance_ = new Waypoint(); - HeaderInfo::default_instance_->InitAsDefaultInstance(); - GLOverlay::default_instance_->InitAsDefaultInstance(); - Obstacle::default_instance_->InitAsDefaultInstance(); - ObstacleList::default_instance_->InitAsDefaultInstance(); - ObstacleMap::default_instance_->InitAsDefaultInstance(); - Path::default_instance_->InitAsDefaultInstance(); - PointCloudXYZI::default_instance_->InitAsDefaultInstance(); - PointCloudXYZI_PointXYZI::default_instance_->InitAsDefaultInstance(); - PointCloudXYZRGB::default_instance_->InitAsDefaultInstance(); - PointCloudXYZRGB_PointXYZRGB::default_instance_->InitAsDefaultInstance(); - RGBDImage::default_instance_->InitAsDefaultInstance(); - Waypoint::default_instance_->InitAsDefaultInstance(); - ::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_pixhawk_2eproto); -} - -// Force AddDescriptors() to be called at static initialization time. -struct StaticDescriptorInitializer_pixhawk_2eproto { - StaticDescriptorInitializer_pixhawk_2eproto() { - protobuf_AddDesc_pixhawk_2eproto(); - } -} static_descriptor_initializer_pixhawk_2eproto_; - - -// =================================================================== - -#ifndef _MSC_VER -const int HeaderInfo::kSourceSysidFieldNumber; -const int HeaderInfo::kSourceCompidFieldNumber; -const int HeaderInfo::kTimestampFieldNumber; -#endif // !_MSC_VER - -HeaderInfo::HeaderInfo() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void HeaderInfo::InitAsDefaultInstance() { -} - -HeaderInfo::HeaderInfo(const HeaderInfo& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void HeaderInfo::SharedCtor() { - _cached_size_ = 0; - source_sysid_ = 0; - source_compid_ = 0; - timestamp_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -HeaderInfo::~HeaderInfo() { - SharedDtor(); -} - -void HeaderInfo::SharedDtor() { - if (this != default_instance_) { - } -} - -void HeaderInfo::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* HeaderInfo::descriptor() { - protobuf_AssignDescriptorsOnce(); - return HeaderInfo_descriptor_; -} - -const HeaderInfo& HeaderInfo::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -HeaderInfo* HeaderInfo::default_instance_ = NULL; - -HeaderInfo* HeaderInfo::New() const { - return new HeaderInfo; -} - -void HeaderInfo::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - source_sysid_ = 0; - source_compid_ = 0; - timestamp_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool HeaderInfo::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required int32 source_sysid = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &source_sysid_))); - set_has_source_sysid(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(16)) goto parse_source_compid; - break; - } - - // required int32 source_compid = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_source_compid: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &source_compid_))); - set_has_source_compid(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(25)) goto parse_timestamp; - break; - } - - // required double timestamp = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_timestamp: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, ×tamp_))); - set_has_timestamp(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void HeaderInfo::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required int32 source_sysid = 1; - if (has_source_sysid()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(1, this->source_sysid(), output); - } - - // required int32 source_compid = 2; - if (has_source_compid()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->source_compid(), output); - } - - // required double timestamp = 3; - if (has_timestamp()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->timestamp(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* HeaderInfo::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required int32 source_sysid = 1; - if (has_source_sysid()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(1, this->source_sysid(), target); - } - - // required int32 source_compid = 2; - if (has_source_compid()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->source_compid(), target); - } - - // required double timestamp = 3; - if (has_timestamp()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->timestamp(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int HeaderInfo::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required int32 source_sysid = 1; - if (has_source_sysid()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->source_sysid()); - } - - // required int32 source_compid = 2; - if (has_source_compid()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->source_compid()); - } - - // required double timestamp = 3; - if (has_timestamp()) { - total_size += 1 + 8; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void HeaderInfo::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const HeaderInfo* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void HeaderInfo::MergeFrom(const HeaderInfo& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_source_sysid()) { - set_source_sysid(from.source_sysid()); - } - if (from.has_source_compid()) { - set_source_compid(from.source_compid()); - } - if (from.has_timestamp()) { - set_timestamp(from.timestamp()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void HeaderInfo::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void HeaderInfo::CopyFrom(const HeaderInfo& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool HeaderInfo::IsInitialized() const { - if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false; - - return true; -} - -void HeaderInfo::Swap(HeaderInfo* other) { - if (other != this) { - std::swap(source_sysid_, other->source_sysid_); - std::swap(source_compid_, other->source_compid_); - std::swap(timestamp_, other->timestamp_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata HeaderInfo::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = HeaderInfo_descriptor_; - metadata.reflection = HeaderInfo_reflection_; - return metadata; -} - - -// =================================================================== - -const ::google::protobuf::EnumDescriptor* GLOverlay_CoordinateFrameType_descriptor() { - protobuf_AssignDescriptorsOnce(); - return GLOverlay_CoordinateFrameType_descriptor_; -} -bool GLOverlay_CoordinateFrameType_IsValid(int value) { - switch(value) { - case 0: - case 1: - return true; - default: - return false; - } -} - -#ifndef _MSC_VER -const GLOverlay_CoordinateFrameType GLOverlay::GLOBAL; -const GLOverlay_CoordinateFrameType GLOverlay::LOCAL; -const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MIN; -const GLOverlay_CoordinateFrameType GLOverlay::CoordinateFrameType_MAX; -const int GLOverlay::CoordinateFrameType_ARRAYSIZE; -#endif // _MSC_VER -const ::google::protobuf::EnumDescriptor* GLOverlay_Mode_descriptor() { - protobuf_AssignDescriptorsOnce(); - return GLOverlay_Mode_descriptor_; -} -bool GLOverlay_Mode_IsValid(int value) { - switch(value) { - case 0: - case 1: - case 2: - case 3: - case 4: - case 5: - case 6: - case 7: - case 8: - case 9: - case 10: - case 11: - case 12: - case 13: - return true; - default: - return false; - } -} - -#ifndef _MSC_VER -const GLOverlay_Mode GLOverlay::POINTS; -const GLOverlay_Mode GLOverlay::LINES; -const GLOverlay_Mode GLOverlay::LINE_STRIP; -const GLOverlay_Mode GLOverlay::LINE_LOOP; -const GLOverlay_Mode GLOverlay::TRIANGLES; -const GLOverlay_Mode GLOverlay::TRIANGLE_STRIP; -const GLOverlay_Mode GLOverlay::TRIANGLE_FAN; -const GLOverlay_Mode GLOverlay::QUADS; -const GLOverlay_Mode GLOverlay::QUAD_STRIP; -const GLOverlay_Mode GLOverlay::POLYGON; -const GLOverlay_Mode GLOverlay::SOLID_CIRCLE; -const GLOverlay_Mode GLOverlay::WIRE_CIRCLE; -const GLOverlay_Mode GLOverlay::SOLID_CUBE; -const GLOverlay_Mode GLOverlay::WIRE_CUBE; -const GLOverlay_Mode GLOverlay::Mode_MIN; -const GLOverlay_Mode GLOverlay::Mode_MAX; -const int GLOverlay::Mode_ARRAYSIZE; -#endif // _MSC_VER -const ::google::protobuf::EnumDescriptor* GLOverlay_Identifier_descriptor() { - protobuf_AssignDescriptorsOnce(); - return GLOverlay_Identifier_descriptor_; -} -bool GLOverlay_Identifier_IsValid(int value) { - switch(value) { - case 14: - case 15: - case 16: - case 17: - case 18: - case 19: - case 20: - case 21: - case 22: - case 23: - case 24: - case 25: - return true; - default: - return false; - } -} - -#ifndef _MSC_VER -const GLOverlay_Identifier GLOverlay::END; -const GLOverlay_Identifier GLOverlay::VERTEX2F; -const GLOverlay_Identifier GLOverlay::VERTEX3F; -const GLOverlay_Identifier GLOverlay::ROTATEF; -const GLOverlay_Identifier GLOverlay::TRANSLATEF; -const GLOverlay_Identifier GLOverlay::SCALEF; -const GLOverlay_Identifier GLOverlay::PUSH_MATRIX; -const GLOverlay_Identifier GLOverlay::POP_MATRIX; -const GLOverlay_Identifier GLOverlay::COLOR3F; -const GLOverlay_Identifier GLOverlay::COLOR4F; -const GLOverlay_Identifier GLOverlay::POINTSIZE; -const GLOverlay_Identifier GLOverlay::LINEWIDTH; -const GLOverlay_Identifier GLOverlay::Identifier_MIN; -const GLOverlay_Identifier GLOverlay::Identifier_MAX; -const int GLOverlay::Identifier_ARRAYSIZE; -#endif // _MSC_VER -#ifndef _MSC_VER -const int GLOverlay::kHeaderFieldNumber; -const int GLOverlay::kNameFieldNumber; -const int GLOverlay::kCoordinateFrameTypeFieldNumber; -const int GLOverlay::kOriginXFieldNumber; -const int GLOverlay::kOriginYFieldNumber; -const int GLOverlay::kOriginZFieldNumber; -const int GLOverlay::kDataFieldNumber; -#endif // !_MSC_VER - -GLOverlay::GLOverlay() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void GLOverlay::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -GLOverlay::GLOverlay(const GLOverlay& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void GLOverlay::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - name_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - coordinateframetype_ = 0; - origin_x_ = 0; - origin_y_ = 0; - origin_z_ = 0; - data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -GLOverlay::~GLOverlay() { - SharedDtor(); -} - -void GLOverlay::SharedDtor() { - if (name_ != &::google::protobuf::internal::kEmptyString) { - delete name_; - } - if (data_ != &::google::protobuf::internal::kEmptyString) { - delete data_; - } - if (this != default_instance_) { - delete header_; - } -} - -void GLOverlay::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* GLOverlay::descriptor() { - protobuf_AssignDescriptorsOnce(); - return GLOverlay_descriptor_; -} - -const GLOverlay& GLOverlay::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -GLOverlay* GLOverlay::default_instance_ = NULL; - -GLOverlay* GLOverlay::New() const { - return new GLOverlay; -} - -void GLOverlay::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - if (has_name()) { - if (name_ != &::google::protobuf::internal::kEmptyString) { - name_->clear(); - } - } - coordinateframetype_ = 0; - origin_x_ = 0; - origin_y_ = 0; - origin_z_ = 0; - if (has_data()) { - if (data_ != &::google::protobuf::internal::kEmptyString) { - data_->clear(); - } - } - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool GLOverlay::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_name; - break; - } - - // optional string name = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_name: - DO_(::google::protobuf::internal::WireFormatLite::ReadString( - input, this->mutable_name())); - ::google::protobuf::internal::WireFormat::VerifyUTF8String( - this->name().data(), this->name().length(), - ::google::protobuf::internal::WireFormat::PARSE); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(24)) goto parse_coordinateFrameType; - break; - } - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_coordinateFrameType: - int value; - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>( - input, &value))); - if (::px::GLOverlay_CoordinateFrameType_IsValid(value)) { - set_coordinateframetype(static_cast< ::px::GLOverlay_CoordinateFrameType >(value)); - } else { - mutable_unknown_fields()->AddVarint(3, value); - } - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(33)) goto parse_origin_x; - break; - } - - // optional double origin_x = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_origin_x: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &origin_x_))); - set_has_origin_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(41)) goto parse_origin_y; - break; - } - - // optional double origin_y = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_origin_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &origin_y_))); - set_has_origin_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(49)) goto parse_origin_z; - break; - } - - // optional double origin_z = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_origin_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &origin_z_))); - set_has_origin_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(58)) goto parse_data; - break; - } - - // optional bytes data = 7; - case 7: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_data: - DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( - input, this->mutable_data())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void GLOverlay::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // optional string name = 2; - if (has_name()) { - ::google::protobuf::internal::WireFormat::VerifyUTF8String( - this->name().data(), this->name().length(), - ::google::protobuf::internal::WireFormat::SERIALIZE); - ::google::protobuf::internal::WireFormatLite::WriteString( - 2, this->name(), output); - } - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - if (has_coordinateframetype()) { - ::google::protobuf::internal::WireFormatLite::WriteEnum( - 3, this->coordinateframetype(), output); - } - - // optional double origin_x = 4; - if (has_origin_x()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->origin_x(), output); - } - - // optional double origin_y = 5; - if (has_origin_y()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->origin_y(), output); - } - - // optional double origin_z = 6; - if (has_origin_z()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->origin_z(), output); - } - - // optional bytes data = 7; - if (has_data()) { - ::google::protobuf::internal::WireFormatLite::WriteBytes( - 7, this->data(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* GLOverlay::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // optional string name = 2; - if (has_name()) { - ::google::protobuf::internal::WireFormat::VerifyUTF8String( - this->name().data(), this->name().length(), - ::google::protobuf::internal::WireFormat::SERIALIZE); - target = - ::google::protobuf::internal::WireFormatLite::WriteStringToArray( - 2, this->name(), target); - } - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - if (has_coordinateframetype()) { - target = ::google::protobuf::internal::WireFormatLite::WriteEnumToArray( - 3, this->coordinateframetype(), target); - } - - // optional double origin_x = 4; - if (has_origin_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->origin_x(), target); - } - - // optional double origin_y = 5; - if (has_origin_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->origin_y(), target); - } - - // optional double origin_z = 6; - if (has_origin_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->origin_z(), target); - } - - // optional bytes data = 7; - if (has_data()) { - target = - ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 7, this->data(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int GLOverlay::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - // optional string name = 2; - if (has_name()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::StringSize( - this->name()); - } - - // optional .px.GLOverlay.CoordinateFrameType coordinateFrameType = 3; - if (has_coordinateframetype()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::EnumSize(this->coordinateframetype()); - } - - // optional double origin_x = 4; - if (has_origin_x()) { - total_size += 1 + 8; - } - - // optional double origin_y = 5; - if (has_origin_y()) { - total_size += 1 + 8; - } - - // optional double origin_z = 6; - if (has_origin_z()) { - total_size += 1 + 8; - } - - // optional bytes data = 7; - if (has_data()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::BytesSize( - this->data()); - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void GLOverlay::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const GLOverlay* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void GLOverlay::MergeFrom(const GLOverlay& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - if (from.has_name()) { - set_name(from.name()); - } - if (from.has_coordinateframetype()) { - set_coordinateframetype(from.coordinateframetype()); - } - if (from.has_origin_x()) { - set_origin_x(from.origin_x()); - } - if (from.has_origin_y()) { - set_origin_y(from.origin_y()); - } - if (from.has_origin_z()) { - set_origin_z(from.origin_z()); - } - if (from.has_data()) { - set_data(from.data()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void GLOverlay::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void GLOverlay::CopyFrom(const GLOverlay& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool GLOverlay::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - return true; -} - -void GLOverlay::Swap(GLOverlay* other) { - if (other != this) { - std::swap(header_, other->header_); - std::swap(name_, other->name_); - std::swap(coordinateframetype_, other->coordinateframetype_); - std::swap(origin_x_, other->origin_x_); - std::swap(origin_y_, other->origin_y_); - std::swap(origin_z_, other->origin_z_); - std::swap(data_, other->data_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata GLOverlay::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = GLOverlay_descriptor_; - metadata.reflection = GLOverlay_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int Obstacle::kXFieldNumber; -const int Obstacle::kYFieldNumber; -const int Obstacle::kZFieldNumber; -const int Obstacle::kLengthFieldNumber; -const int Obstacle::kWidthFieldNumber; -const int Obstacle::kHeightFieldNumber; -#endif // !_MSC_VER - -Obstacle::Obstacle() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void Obstacle::InitAsDefaultInstance() { -} - -Obstacle::Obstacle(const Obstacle& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void Obstacle::SharedCtor() { - _cached_size_ = 0; - x_ = 0; - y_ = 0; - z_ = 0; - length_ = 0; - width_ = 0; - height_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -Obstacle::~Obstacle() { - SharedDtor(); -} - -void Obstacle::SharedDtor() { - if (this != default_instance_) { - } -} - -void Obstacle::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* Obstacle::descriptor() { - protobuf_AssignDescriptorsOnce(); - return Obstacle_descriptor_; -} - -const Obstacle& Obstacle::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -Obstacle* Obstacle::default_instance_ = NULL; - -Obstacle* Obstacle::New() const { - return new Obstacle; -} - -void Obstacle::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - x_ = 0; - y_ = 0; - z_ = 0; - length_ = 0; - width_ = 0; - height_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool Obstacle::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // optional float x = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &x_))); - set_has_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(21)) goto parse_y; - break; - } - - // optional float y = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &y_))); - set_has_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(29)) goto parse_z; - break; - } - - // optional float z = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &z_))); - set_has_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(37)) goto parse_length; - break; - } - - // optional float length = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_length: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &length_))); - set_has_length(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(45)) goto parse_width; - break; - } - - // optional float width = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_width: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &width_))); - set_has_width(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(53)) goto parse_height; - break; - } - - // optional float height = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_height: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &height_))); - set_has_height(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void Obstacle::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // optional float x = 1; - if (has_x()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output); - } - - // optional float y = 2; - if (has_y()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output); - } - - // optional float z = 3; - if (has_z()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output); - } - - // optional float length = 4; - if (has_length()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->length(), output); - } - - // optional float width = 5; - if (has_width()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(5, this->width(), output); - } - - // optional float height = 6; - if (has_height()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(6, this->height(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* Obstacle::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // optional float x = 1; - if (has_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target); - } - - // optional float y = 2; - if (has_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target); - } - - // optional float z = 3; - if (has_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target); - } - - // optional float length = 4; - if (has_length()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->length(), target); - } - - // optional float width = 5; - if (has_width()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(5, this->width(), target); - } - - // optional float height = 6; - if (has_height()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(6, this->height(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int Obstacle::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // optional float x = 1; - if (has_x()) { - total_size += 1 + 4; - } - - // optional float y = 2; - if (has_y()) { - total_size += 1 + 4; - } - - // optional float z = 3; - if (has_z()) { - total_size += 1 + 4; - } - - // optional float length = 4; - if (has_length()) { - total_size += 1 + 4; - } - - // optional float width = 5; - if (has_width()) { - total_size += 1 + 4; - } - - // optional float height = 6; - if (has_height()) { - total_size += 1 + 4; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void Obstacle::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const Obstacle* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void Obstacle::MergeFrom(const Obstacle& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_x()) { - set_x(from.x()); - } - if (from.has_y()) { - set_y(from.y()); - } - if (from.has_z()) { - set_z(from.z()); - } - if (from.has_length()) { - set_length(from.length()); - } - if (from.has_width()) { - set_width(from.width()); - } - if (from.has_height()) { - set_height(from.height()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void Obstacle::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void Obstacle::CopyFrom(const Obstacle& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool Obstacle::IsInitialized() const { - - return true; -} - -void Obstacle::Swap(Obstacle* other) { - if (other != this) { - std::swap(x_, other->x_); - std::swap(y_, other->y_); - std::swap(z_, other->z_); - std::swap(length_, other->length_); - std::swap(width_, other->width_); - std::swap(height_, other->height_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata Obstacle::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = Obstacle_descriptor_; - metadata.reflection = Obstacle_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int ObstacleList::kHeaderFieldNumber; -const int ObstacleList::kObstaclesFieldNumber; -#endif // !_MSC_VER - -ObstacleList::ObstacleList() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void ObstacleList::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -ObstacleList::ObstacleList(const ObstacleList& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void ObstacleList::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -ObstacleList::~ObstacleList() { - SharedDtor(); -} - -void ObstacleList::SharedDtor() { - if (this != default_instance_) { - delete header_; - } -} - -void ObstacleList::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* ObstacleList::descriptor() { - protobuf_AssignDescriptorsOnce(); - return ObstacleList_descriptor_; -} - -const ObstacleList& ObstacleList::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -ObstacleList* ObstacleList::default_instance_ = NULL; - -ObstacleList* ObstacleList::New() const { - return new ObstacleList; -} - -void ObstacleList::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - } - obstacles_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool ObstacleList::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_obstacles; - break; - } - - // repeated .px.Obstacle obstacles = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_obstacles: - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, add_obstacles())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_obstacles; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void ObstacleList::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // repeated .px.Obstacle obstacles = 2; - for (int i = 0; i < this->obstacles_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 2, this->obstacles(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* ObstacleList::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // repeated .px.Obstacle obstacles = 2; - for (int i = 0; i < this->obstacles_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 2, this->obstacles(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int ObstacleList::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - } - // repeated .px.Obstacle obstacles = 2; - total_size += 1 * this->obstacles_size(); - for (int i = 0; i < this->obstacles_size(); i++) { - total_size += - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->obstacles(i)); - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void ObstacleList::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const ObstacleList* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void ObstacleList::MergeFrom(const ObstacleList& from) { - GOOGLE_CHECK_NE(&from, this); - obstacles_.MergeFrom(from.obstacles_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void ObstacleList::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void ObstacleList::CopyFrom(const ObstacleList& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool ObstacleList::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - return true; -} - -void ObstacleList::Swap(ObstacleList* other) { - if (other != this) { - std::swap(header_, other->header_); - obstacles_.Swap(&other->obstacles_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata ObstacleList::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = ObstacleList_descriptor_; - metadata.reflection = ObstacleList_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int ObstacleMap::kHeaderFieldNumber; -const int ObstacleMap::kTypeFieldNumber; -const int ObstacleMap::kResolutionFieldNumber; -const int ObstacleMap::kRowsFieldNumber; -const int ObstacleMap::kColsFieldNumber; -const int ObstacleMap::kMapR0FieldNumber; -const int ObstacleMap::kMapC0FieldNumber; -const int ObstacleMap::kArrayR0FieldNumber; -const int ObstacleMap::kArrayC0FieldNumber; -const int ObstacleMap::kDataFieldNumber; -#endif // !_MSC_VER - -ObstacleMap::ObstacleMap() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void ObstacleMap::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -ObstacleMap::ObstacleMap(const ObstacleMap& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void ObstacleMap::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - type_ = 0; - resolution_ = 0; - rows_ = 0; - cols_ = 0; - mapr0_ = 0; - mapc0_ = 0; - arrayr0_ = 0; - arrayc0_ = 0; - data_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -ObstacleMap::~ObstacleMap() { - SharedDtor(); -} - -void ObstacleMap::SharedDtor() { - if (data_ != &::google::protobuf::internal::kEmptyString) { - delete data_; - } - if (this != default_instance_) { - delete header_; - } -} - -void ObstacleMap::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* ObstacleMap::descriptor() { - protobuf_AssignDescriptorsOnce(); - return ObstacleMap_descriptor_; -} - -const ObstacleMap& ObstacleMap::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -ObstacleMap* ObstacleMap::default_instance_ = NULL; - -ObstacleMap* ObstacleMap::New() const { - return new ObstacleMap; -} - -void ObstacleMap::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - type_ = 0; - resolution_ = 0; - rows_ = 0; - cols_ = 0; - mapr0_ = 0; - mapc0_ = 0; - arrayr0_ = 0; - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { - arrayc0_ = 0; - if (has_data()) { - if (data_ != &::google::protobuf::internal::kEmptyString) { - data_->clear(); - } - } - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool ObstacleMap::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(16)) goto parse_type; - break; - } - - // required int32 type = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_type: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &type_))); - set_has_type(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(29)) goto parse_resolution; - break; - } - - // optional float resolution = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_resolution: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &resolution_))); - set_has_resolution(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(32)) goto parse_rows; - break; - } - - // optional int32 rows = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_rows: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &rows_))); - set_has_rows(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(40)) goto parse_cols; - break; - } - - // optional int32 cols = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_cols: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &cols_))); - set_has_cols(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(48)) goto parse_mapR0; - break; - } - - // optional int32 mapR0 = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_mapR0: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &mapr0_))); - set_has_mapr0(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(56)) goto parse_mapC0; - break; - } - - // optional int32 mapC0 = 7; - case 7: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_mapC0: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &mapc0_))); - set_has_mapc0(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(64)) goto parse_arrayR0; - break; - } - - // optional int32 arrayR0 = 8; - case 8: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_arrayR0: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &arrayr0_))); - set_has_arrayr0(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(72)) goto parse_arrayC0; - break; - } - - // optional int32 arrayC0 = 9; - case 9: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_arrayC0: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::int32, ::google::protobuf::internal::WireFormatLite::TYPE_INT32>( - input, &arrayc0_))); - set_has_arrayc0(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(82)) goto parse_data; - break; - } - - // optional bytes data = 10; - case 10: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_data: - DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( - input, this->mutable_data())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void ObstacleMap::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // required int32 type = 2; - if (has_type()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(2, this->type(), output); - } - - // optional float resolution = 3; - if (has_resolution()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->resolution(), output); - } - - // optional int32 rows = 4; - if (has_rows()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(4, this->rows(), output); - } - - // optional int32 cols = 5; - if (has_cols()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(5, this->cols(), output); - } - - // optional int32 mapR0 = 6; - if (has_mapr0()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(6, this->mapr0(), output); - } - - // optional int32 mapC0 = 7; - if (has_mapc0()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(7, this->mapc0(), output); - } - - // optional int32 arrayR0 = 8; - if (has_arrayr0()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(8, this->arrayr0(), output); - } - - // optional int32 arrayC0 = 9; - if (has_arrayc0()) { - ::google::protobuf::internal::WireFormatLite::WriteInt32(9, this->arrayc0(), output); - } - - // optional bytes data = 10; - if (has_data()) { - ::google::protobuf::internal::WireFormatLite::WriteBytes( - 10, this->data(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* ObstacleMap::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // required int32 type = 2; - if (has_type()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(2, this->type(), target); - } - - // optional float resolution = 3; - if (has_resolution()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->resolution(), target); - } - - // optional int32 rows = 4; - if (has_rows()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(4, this->rows(), target); - } - - // optional int32 cols = 5; - if (has_cols()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(5, this->cols(), target); - } - - // optional int32 mapR0 = 6; - if (has_mapr0()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(6, this->mapr0(), target); - } - - // optional int32 mapC0 = 7; - if (has_mapc0()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(7, this->mapc0(), target); - } - - // optional int32 arrayR0 = 8; - if (has_arrayr0()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(8, this->arrayr0(), target); - } - - // optional int32 arrayC0 = 9; - if (has_arrayc0()) { - target = ::google::protobuf::internal::WireFormatLite::WriteInt32ToArray(9, this->arrayc0(), target); - } - - // optional bytes data = 10; - if (has_data()) { - target = - ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 10, this->data(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int ObstacleMap::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - // required int32 type = 2; - if (has_type()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->type()); - } - - // optional float resolution = 3; - if (has_resolution()) { - total_size += 1 + 4; - } - - // optional int32 rows = 4; - if (has_rows()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->rows()); - } - - // optional int32 cols = 5; - if (has_cols()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->cols()); - } - - // optional int32 mapR0 = 6; - if (has_mapr0()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->mapr0()); - } - - // optional int32 mapC0 = 7; - if (has_mapc0()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->mapc0()); - } - - // optional int32 arrayR0 = 8; - if (has_arrayr0()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->arrayr0()); - } - - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { - // optional int32 arrayC0 = 9; - if (has_arrayc0()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::Int32Size( - this->arrayc0()); - } - - // optional bytes data = 10; - if (has_data()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::BytesSize( - this->data()); - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void ObstacleMap::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const ObstacleMap* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void ObstacleMap::MergeFrom(const ObstacleMap& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - if (from.has_type()) { - set_type(from.type()); - } - if (from.has_resolution()) { - set_resolution(from.resolution()); - } - if (from.has_rows()) { - set_rows(from.rows()); - } - if (from.has_cols()) { - set_cols(from.cols()); - } - if (from.has_mapr0()) { - set_mapr0(from.mapr0()); - } - if (from.has_mapc0()) { - set_mapc0(from.mapc0()); - } - if (from.has_arrayr0()) { - set_arrayr0(from.arrayr0()); - } - } - if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) { - if (from.has_arrayc0()) { - set_arrayc0(from.arrayc0()); - } - if (from.has_data()) { - set_data(from.data()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void ObstacleMap::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void ObstacleMap::CopyFrom(const ObstacleMap& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool ObstacleMap::IsInitialized() const { - if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - return true; -} - -void ObstacleMap::Swap(ObstacleMap* other) { - if (other != this) { - std::swap(header_, other->header_); - std::swap(type_, other->type_); - std::swap(resolution_, other->resolution_); - std::swap(rows_, other->rows_); - std::swap(cols_, other->cols_); - std::swap(mapr0_, other->mapr0_); - std::swap(mapc0_, other->mapc0_); - std::swap(arrayr0_, other->arrayr0_); - std::swap(arrayc0_, other->arrayc0_); - std::swap(data_, other->data_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata ObstacleMap::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = ObstacleMap_descriptor_; - metadata.reflection = ObstacleMap_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int Path::kHeaderFieldNumber; -const int Path::kWaypointsFieldNumber; -#endif // !_MSC_VER - -Path::Path() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void Path::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -Path::Path(const Path& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void Path::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -Path::~Path() { - SharedDtor(); -} - -void Path::SharedDtor() { - if (this != default_instance_) { - delete header_; - } -} - -void Path::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* Path::descriptor() { - protobuf_AssignDescriptorsOnce(); - return Path_descriptor_; -} - -const Path& Path::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -Path* Path::default_instance_ = NULL; - -Path* Path::New() const { - return new Path; -} - -void Path::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - } - waypoints_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool Path::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_waypoints; - break; - } - - // repeated .px.Waypoint waypoints = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_waypoints: - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, add_waypoints())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_waypoints; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void Path::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // repeated .px.Waypoint waypoints = 2; - for (int i = 0; i < this->waypoints_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 2, this->waypoints(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* Path::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // repeated .px.Waypoint waypoints = 2; - for (int i = 0; i < this->waypoints_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 2, this->waypoints(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int Path::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - } - // repeated .px.Waypoint waypoints = 2; - total_size += 1 * this->waypoints_size(); - for (int i = 0; i < this->waypoints_size(); i++) { - total_size += - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->waypoints(i)); - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void Path::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const Path* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void Path::MergeFrom(const Path& from) { - GOOGLE_CHECK_NE(&from, this); - waypoints_.MergeFrom(from.waypoints_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void Path::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void Path::CopyFrom(const Path& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool Path::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - for (int i = 0; i < waypoints_size(); i++) { - if (!this->waypoints(i).IsInitialized()) return false; - } - return true; -} - -void Path::Swap(Path* other) { - if (other != this) { - std::swap(header_, other->header_); - waypoints_.Swap(&other->waypoints_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata Path::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = Path_descriptor_; - metadata.reflection = Path_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int PointCloudXYZI_PointXYZI::kXFieldNumber; -const int PointCloudXYZI_PointXYZI::kYFieldNumber; -const int PointCloudXYZI_PointXYZI::kZFieldNumber; -const int PointCloudXYZI_PointXYZI::kIntensityFieldNumber; -#endif // !_MSC_VER - -PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void PointCloudXYZI_PointXYZI::InitAsDefaultInstance() { -} - -PointCloudXYZI_PointXYZI::PointCloudXYZI_PointXYZI(const PointCloudXYZI_PointXYZI& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void PointCloudXYZI_PointXYZI::SharedCtor() { - _cached_size_ = 0; - x_ = 0; - y_ = 0; - z_ = 0; - intensity_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -PointCloudXYZI_PointXYZI::~PointCloudXYZI_PointXYZI() { - SharedDtor(); -} - -void PointCloudXYZI_PointXYZI::SharedDtor() { - if (this != default_instance_) { - } -} - -void PointCloudXYZI_PointXYZI::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* PointCloudXYZI_PointXYZI::descriptor() { - protobuf_AssignDescriptorsOnce(); - return PointCloudXYZI_PointXYZI_descriptor_; -} - -const PointCloudXYZI_PointXYZI& PointCloudXYZI_PointXYZI::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::default_instance_ = NULL; - -PointCloudXYZI_PointXYZI* PointCloudXYZI_PointXYZI::New() const { - return new PointCloudXYZI_PointXYZI; -} - -void PointCloudXYZI_PointXYZI::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - x_ = 0; - y_ = 0; - z_ = 0; - intensity_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool PointCloudXYZI_PointXYZI::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required float x = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &x_))); - set_has_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(21)) goto parse_y; - break; - } - - // required float y = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &y_))); - set_has_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(29)) goto parse_z; - break; - } - - // required float z = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &z_))); - set_has_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(37)) goto parse_intensity; - break; - } - - // required float intensity = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_intensity: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &intensity_))); - set_has_intensity(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void PointCloudXYZI_PointXYZI::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required float x = 1; - if (has_x()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output); - } - - // required float y = 2; - if (has_y()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output); - } - - // required float z = 3; - if (has_z()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output); - } - - // required float intensity = 4; - if (has_intensity()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->intensity(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* PointCloudXYZI_PointXYZI::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required float x = 1; - if (has_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target); - } - - // required float y = 2; - if (has_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target); - } - - // required float z = 3; - if (has_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target); - } - - // required float intensity = 4; - if (has_intensity()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->intensity(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int PointCloudXYZI_PointXYZI::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required float x = 1; - if (has_x()) { - total_size += 1 + 4; - } - - // required float y = 2; - if (has_y()) { - total_size += 1 + 4; - } - - // required float z = 3; - if (has_z()) { - total_size += 1 + 4; - } - - // required float intensity = 4; - if (has_intensity()) { - total_size += 1 + 4; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void PointCloudXYZI_PointXYZI::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const PointCloudXYZI_PointXYZI* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void PointCloudXYZI_PointXYZI::MergeFrom(const PointCloudXYZI_PointXYZI& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_x()) { - set_x(from.x()); - } - if (from.has_y()) { - set_y(from.y()); - } - if (from.has_z()) { - set_z(from.z()); - } - if (from.has_intensity()) { - set_intensity(from.intensity()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void PointCloudXYZI_PointXYZI::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void PointCloudXYZI_PointXYZI::CopyFrom(const PointCloudXYZI_PointXYZI& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool PointCloudXYZI_PointXYZI::IsInitialized() const { - if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false; - - return true; -} - -void PointCloudXYZI_PointXYZI::Swap(PointCloudXYZI_PointXYZI* other) { - if (other != this) { - std::swap(x_, other->x_); - std::swap(y_, other->y_); - std::swap(z_, other->z_); - std::swap(intensity_, other->intensity_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata PointCloudXYZI_PointXYZI::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = PointCloudXYZI_PointXYZI_descriptor_; - metadata.reflection = PointCloudXYZI_PointXYZI_reflection_; - return metadata; -} - - -// ------------------------------------------------------------------- - -#ifndef _MSC_VER -const int PointCloudXYZI::kHeaderFieldNumber; -const int PointCloudXYZI::kPointsFieldNumber; -#endif // !_MSC_VER - -PointCloudXYZI::PointCloudXYZI() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void PointCloudXYZI::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -PointCloudXYZI::PointCloudXYZI(const PointCloudXYZI& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void PointCloudXYZI::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -PointCloudXYZI::~PointCloudXYZI() { - SharedDtor(); -} - -void PointCloudXYZI::SharedDtor() { - if (this != default_instance_) { - delete header_; - } -} - -void PointCloudXYZI::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* PointCloudXYZI::descriptor() { - protobuf_AssignDescriptorsOnce(); - return PointCloudXYZI_descriptor_; -} - -const PointCloudXYZI& PointCloudXYZI::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -PointCloudXYZI* PointCloudXYZI::default_instance_ = NULL; - -PointCloudXYZI* PointCloudXYZI::New() const { - return new PointCloudXYZI; -} - -void PointCloudXYZI::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - } - points_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool PointCloudXYZI::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_points; - break; - } - - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_points: - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, add_points())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_points; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void PointCloudXYZI::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - for (int i = 0; i < this->points_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 2, this->points(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* PointCloudXYZI::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - for (int i = 0; i < this->points_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 2, this->points(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int PointCloudXYZI::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - } - // repeated .px.PointCloudXYZI.PointXYZI points = 2; - total_size += 1 * this->points_size(); - for (int i = 0; i < this->points_size(); i++) { - total_size += - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->points(i)); - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void PointCloudXYZI::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const PointCloudXYZI* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void PointCloudXYZI::MergeFrom(const PointCloudXYZI& from) { - GOOGLE_CHECK_NE(&from, this); - points_.MergeFrom(from.points_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void PointCloudXYZI::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void PointCloudXYZI::CopyFrom(const PointCloudXYZI& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool PointCloudXYZI::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - for (int i = 0; i < points_size(); i++) { - if (!this->points(i).IsInitialized()) return false; - } - return true; -} - -void PointCloudXYZI::Swap(PointCloudXYZI* other) { - if (other != this) { - std::swap(header_, other->header_); - points_.Swap(&other->points_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata PointCloudXYZI::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = PointCloudXYZI_descriptor_; - metadata.reflection = PointCloudXYZI_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int PointCloudXYZRGB_PointXYZRGB::kXFieldNumber; -const int PointCloudXYZRGB_PointXYZRGB::kYFieldNumber; -const int PointCloudXYZRGB_PointXYZRGB::kZFieldNumber; -const int PointCloudXYZRGB_PointXYZRGB::kRgbFieldNumber; -#endif // !_MSC_VER - -PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void PointCloudXYZRGB_PointXYZRGB::InitAsDefaultInstance() { -} - -PointCloudXYZRGB_PointXYZRGB::PointCloudXYZRGB_PointXYZRGB(const PointCloudXYZRGB_PointXYZRGB& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void PointCloudXYZRGB_PointXYZRGB::SharedCtor() { - _cached_size_ = 0; - x_ = 0; - y_ = 0; - z_ = 0; - rgb_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -PointCloudXYZRGB_PointXYZRGB::~PointCloudXYZRGB_PointXYZRGB() { - SharedDtor(); -} - -void PointCloudXYZRGB_PointXYZRGB::SharedDtor() { - if (this != default_instance_) { - } -} - -void PointCloudXYZRGB_PointXYZRGB::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* PointCloudXYZRGB_PointXYZRGB::descriptor() { - protobuf_AssignDescriptorsOnce(); - return PointCloudXYZRGB_PointXYZRGB_descriptor_; -} - -const PointCloudXYZRGB_PointXYZRGB& PointCloudXYZRGB_PointXYZRGB::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::default_instance_ = NULL; - -PointCloudXYZRGB_PointXYZRGB* PointCloudXYZRGB_PointXYZRGB::New() const { - return new PointCloudXYZRGB_PointXYZRGB; -} - -void PointCloudXYZRGB_PointXYZRGB::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - x_ = 0; - y_ = 0; - z_ = 0; - rgb_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool PointCloudXYZRGB_PointXYZRGB::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required float x = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &x_))); - set_has_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(21)) goto parse_y; - break; - } - - // required float y = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &y_))); - set_has_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(29)) goto parse_z; - break; - } - - // required float z = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &z_))); - set_has_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(37)) goto parse_rgb; - break; - } - - // required float rgb = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_rgb: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &rgb_))); - set_has_rgb(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required float x = 1; - if (has_x()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(1, this->x(), output); - } - - // required float y = 2; - if (has_y()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(2, this->y(), output); - } - - // required float z = 3; - if (has_z()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(3, this->z(), output); - } - - // required float rgb = 4; - if (has_rgb()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(4, this->rgb(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* PointCloudXYZRGB_PointXYZRGB::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required float x = 1; - if (has_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(1, this->x(), target); - } - - // required float y = 2; - if (has_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(2, this->y(), target); - } - - // required float z = 3; - if (has_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(3, this->z(), target); - } - - // required float rgb = 4; - if (has_rgb()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(4, this->rgb(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int PointCloudXYZRGB_PointXYZRGB::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required float x = 1; - if (has_x()) { - total_size += 1 + 4; - } - - // required float y = 2; - if (has_y()) { - total_size += 1 + 4; - } - - // required float z = 3; - if (has_z()) { - total_size += 1 + 4; - } - - // required float rgb = 4; - if (has_rgb()) { - total_size += 1 + 4; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const PointCloudXYZRGB_PointXYZRGB* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void PointCloudXYZRGB_PointXYZRGB::MergeFrom(const PointCloudXYZRGB_PointXYZRGB& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_x()) { - set_x(from.x()); - } - if (from.has_y()) { - set_y(from.y()); - } - if (from.has_z()) { - set_z(from.z()); - } - if (from.has_rgb()) { - set_rgb(from.rgb()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void PointCloudXYZRGB_PointXYZRGB::CopyFrom(const PointCloudXYZRGB_PointXYZRGB& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool PointCloudXYZRGB_PointXYZRGB::IsInitialized() const { - if ((_has_bits_[0] & 0x0000000f) != 0x0000000f) return false; - - return true; -} - -void PointCloudXYZRGB_PointXYZRGB::Swap(PointCloudXYZRGB_PointXYZRGB* other) { - if (other != this) { - std::swap(x_, other->x_); - std::swap(y_, other->y_); - std::swap(z_, other->z_); - std::swap(rgb_, other->rgb_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata PointCloudXYZRGB_PointXYZRGB::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = PointCloudXYZRGB_PointXYZRGB_descriptor_; - metadata.reflection = PointCloudXYZRGB_PointXYZRGB_reflection_; - return metadata; -} - - -// ------------------------------------------------------------------- - -#ifndef _MSC_VER -const int PointCloudXYZRGB::kHeaderFieldNumber; -const int PointCloudXYZRGB::kPointsFieldNumber; -#endif // !_MSC_VER - -PointCloudXYZRGB::PointCloudXYZRGB() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void PointCloudXYZRGB::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -PointCloudXYZRGB::PointCloudXYZRGB(const PointCloudXYZRGB& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void PointCloudXYZRGB::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -PointCloudXYZRGB::~PointCloudXYZRGB() { - SharedDtor(); -} - -void PointCloudXYZRGB::SharedDtor() { - if (this != default_instance_) { - delete header_; - } -} - -void PointCloudXYZRGB::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* PointCloudXYZRGB::descriptor() { - protobuf_AssignDescriptorsOnce(); - return PointCloudXYZRGB_descriptor_; -} - -const PointCloudXYZRGB& PointCloudXYZRGB::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -PointCloudXYZRGB* PointCloudXYZRGB::default_instance_ = NULL; - -PointCloudXYZRGB* PointCloudXYZRGB::New() const { - return new PointCloudXYZRGB; -} - -void PointCloudXYZRGB::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - } - points_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool PointCloudXYZRGB::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_points; - break; - } - - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_points: - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, add_points())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(18)) goto parse_points; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void PointCloudXYZRGB::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - for (int i = 0; i < this->points_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 2, this->points(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* PointCloudXYZRGB::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - for (int i = 0; i < this->points_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 2, this->points(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int PointCloudXYZRGB::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - } - // repeated .px.PointCloudXYZRGB.PointXYZRGB points = 2; - total_size += 1 * this->points_size(); - for (int i = 0; i < this->points_size(); i++) { - total_size += - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->points(i)); - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void PointCloudXYZRGB::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const PointCloudXYZRGB* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void PointCloudXYZRGB::MergeFrom(const PointCloudXYZRGB& from) { - GOOGLE_CHECK_NE(&from, this); - points_.MergeFrom(from.points_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void PointCloudXYZRGB::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void PointCloudXYZRGB::CopyFrom(const PointCloudXYZRGB& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool PointCloudXYZRGB::IsInitialized() const { - if ((_has_bits_[0] & 0x00000001) != 0x00000001) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - for (int i = 0; i < points_size(); i++) { - if (!this->points(i).IsInitialized()) return false; - } - return true; -} - -void PointCloudXYZRGB::Swap(PointCloudXYZRGB* other) { - if (other != this) { - std::swap(header_, other->header_); - points_.Swap(&other->points_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata PointCloudXYZRGB::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = PointCloudXYZRGB_descriptor_; - metadata.reflection = PointCloudXYZRGB_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int RGBDImage::kHeaderFieldNumber; -const int RGBDImage::kColsFieldNumber; -const int RGBDImage::kRowsFieldNumber; -const int RGBDImage::kStep1FieldNumber; -const int RGBDImage::kType1FieldNumber; -const int RGBDImage::kImageData1FieldNumber; -const int RGBDImage::kStep2FieldNumber; -const int RGBDImage::kType2FieldNumber; -const int RGBDImage::kImageData2FieldNumber; -const int RGBDImage::kCameraConfigFieldNumber; -const int RGBDImage::kCameraTypeFieldNumber; -const int RGBDImage::kRollFieldNumber; -const int RGBDImage::kPitchFieldNumber; -const int RGBDImage::kYawFieldNumber; -const int RGBDImage::kLonFieldNumber; -const int RGBDImage::kLatFieldNumber; -const int RGBDImage::kAltFieldNumber; -const int RGBDImage::kGroundXFieldNumber; -const int RGBDImage::kGroundYFieldNumber; -const int RGBDImage::kGroundZFieldNumber; -const int RGBDImage::kCameraMatrixFieldNumber; -#endif // !_MSC_VER - -RGBDImage::RGBDImage() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void RGBDImage::InitAsDefaultInstance() { - header_ = const_cast< ::px::HeaderInfo*>(&::px::HeaderInfo::default_instance()); -} - -RGBDImage::RGBDImage(const RGBDImage& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void RGBDImage::SharedCtor() { - _cached_size_ = 0; - header_ = NULL; - cols_ = 0u; - rows_ = 0u; - step1_ = 0u; - type1_ = 0u; - imagedata1_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - step2_ = 0u; - type2_ = 0u; - imagedata2_ = const_cast< ::std::string*>(&::google::protobuf::internal::kEmptyString); - camera_config_ = 0u; - camera_type_ = 0u; - roll_ = 0; - pitch_ = 0; - yaw_ = 0; - lon_ = 0; - lat_ = 0; - alt_ = 0; - ground_x_ = 0; - ground_y_ = 0; - ground_z_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -RGBDImage::~RGBDImage() { - SharedDtor(); -} - -void RGBDImage::SharedDtor() { - if (imagedata1_ != &::google::protobuf::internal::kEmptyString) { - delete imagedata1_; - } - if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { - delete imagedata2_; - } - if (this != default_instance_) { - delete header_; - } -} - -void RGBDImage::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* RGBDImage::descriptor() { - protobuf_AssignDescriptorsOnce(); - return RGBDImage_descriptor_; -} - -const RGBDImage& RGBDImage::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -RGBDImage* RGBDImage::default_instance_ = NULL; - -RGBDImage* RGBDImage::New() const { - return new RGBDImage; -} - -void RGBDImage::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (has_header()) { - if (header_ != NULL) header_->::px::HeaderInfo::Clear(); - } - cols_ = 0u; - rows_ = 0u; - step1_ = 0u; - type1_ = 0u; - if (has_imagedata1()) { - if (imagedata1_ != &::google::protobuf::internal::kEmptyString) { - imagedata1_->clear(); - } - } - step2_ = 0u; - type2_ = 0u; - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { - if (has_imagedata2()) { - if (imagedata2_ != &::google::protobuf::internal::kEmptyString) { - imagedata2_->clear(); - } - } - camera_config_ = 0u; - camera_type_ = 0u; - roll_ = 0; - pitch_ = 0; - yaw_ = 0; - lon_ = 0; - lat_ = 0; - } - if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) { - alt_ = 0; - ground_x_ = 0; - ground_y_ = 0; - ground_z_ = 0; - } - camera_matrix_.Clear(); - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool RGBDImage::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required .px.HeaderInfo header = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual( - input, mutable_header())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(16)) goto parse_cols; - break; - } - - // required uint32 cols = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_cols: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &cols_))); - set_has_cols(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(24)) goto parse_rows; - break; - } - - // required uint32 rows = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_rows: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &rows_))); - set_has_rows(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(32)) goto parse_step1; - break; - } - - // required uint32 step1 = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_step1: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &step1_))); - set_has_step1(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(40)) goto parse_type1; - break; - } - - // required uint32 type1 = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_type1: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &type1_))); - set_has_type1(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(50)) goto parse_imageData1; - break; - } - - // required bytes imageData1 = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_imageData1: - DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( - input, this->mutable_imagedata1())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(56)) goto parse_step2; - break; - } - - // required uint32 step2 = 7; - case 7: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_step2: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &step2_))); - set_has_step2(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(64)) goto parse_type2; - break; - } - - // required uint32 type2 = 8; - case 8: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_type2: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &type2_))); - set_has_type2(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(74)) goto parse_imageData2; - break; - } - - // required bytes imageData2 = 9; - case 9: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) { - parse_imageData2: - DO_(::google::protobuf::internal::WireFormatLite::ReadBytes( - input, this->mutable_imagedata2())); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(80)) goto parse_camera_config; - break; - } - - // optional uint32 camera_config = 10; - case 10: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_camera_config: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &camera_config_))); - set_has_camera_config(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(88)) goto parse_camera_type; - break; - } - - // optional uint32 camera_type = 11; - case 11: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) { - parse_camera_type: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - ::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>( - input, &camera_type_))); - set_has_camera_type(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(101)) goto parse_roll; - break; - } - - // optional float roll = 12; - case 12: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_roll: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &roll_))); - set_has_roll(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(109)) goto parse_pitch; - break; - } - - // optional float pitch = 13; - case 13: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_pitch: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &pitch_))); - set_has_pitch(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(117)) goto parse_yaw; - break; - } - - // optional float yaw = 14; - case 14: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_yaw: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &yaw_))); - set_has_yaw(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(125)) goto parse_lon; - break; - } - - // optional float lon = 15; - case 15: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_lon: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &lon_))); - set_has_lon(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(133)) goto parse_lat; - break; - } - - // optional float lat = 16; - case 16: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_lat: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &lat_))); - set_has_lat(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(141)) goto parse_alt; - break; - } - - // optional float alt = 17; - case 17: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_alt: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &alt_))); - set_has_alt(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(149)) goto parse_ground_x; - break; - } - - // optional float ground_x = 18; - case 18: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_ground_x: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &ground_x_))); - set_has_ground_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(157)) goto parse_ground_y; - break; - } - - // optional float ground_y = 19; - case 19: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_ground_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &ground_y_))); - set_has_ground_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(165)) goto parse_ground_z; - break; - } - - // optional float ground_z = 20; - case 20: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_ground_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, &ground_z_))); - set_has_ground_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(173)) goto parse_camera_matrix; - break; - } - - // repeated float camera_matrix = 21; - case 21: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) { - parse_camera_matrix: - DO_((::google::protobuf::internal::WireFormatLite::ReadRepeatedPrimitive< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - 2, 173, input, this->mutable_camera_matrix()))); - } else if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) - == ::google::protobuf::internal::WireFormatLite:: - WIRETYPE_LENGTH_DELIMITED) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPackedPrimitiveNoInline< - float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>( - input, this->mutable_camera_matrix()))); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(173)) goto parse_camera_matrix; - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void RGBDImage::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - ::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray( - 1, this->header(), output); - } - - // required uint32 cols = 2; - if (has_cols()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(2, this->cols(), output); - } - - // required uint32 rows = 3; - if (has_rows()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(3, this->rows(), output); - } - - // required uint32 step1 = 4; - if (has_step1()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(4, this->step1(), output); - } - - // required uint32 type1 = 5; - if (has_type1()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(5, this->type1(), output); - } - - // required bytes imageData1 = 6; - if (has_imagedata1()) { - ::google::protobuf::internal::WireFormatLite::WriteBytes( - 6, this->imagedata1(), output); - } - - // required uint32 step2 = 7; - if (has_step2()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(7, this->step2(), output); - } - - // required uint32 type2 = 8; - if (has_type2()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(8, this->type2(), output); - } - - // required bytes imageData2 = 9; - if (has_imagedata2()) { - ::google::protobuf::internal::WireFormatLite::WriteBytes( - 9, this->imagedata2(), output); - } - - // optional uint32 camera_config = 10; - if (has_camera_config()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(10, this->camera_config(), output); - } - - // optional uint32 camera_type = 11; - if (has_camera_type()) { - ::google::protobuf::internal::WireFormatLite::WriteUInt32(11, this->camera_type(), output); - } - - // optional float roll = 12; - if (has_roll()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(12, this->roll(), output); - } - - // optional float pitch = 13; - if (has_pitch()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(13, this->pitch(), output); - } - - // optional float yaw = 14; - if (has_yaw()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(14, this->yaw(), output); - } - - // optional float lon = 15; - if (has_lon()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(15, this->lon(), output); - } - - // optional float lat = 16; - if (has_lat()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(16, this->lat(), output); - } - - // optional float alt = 17; - if (has_alt()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(17, this->alt(), output); - } - - // optional float ground_x = 18; - if (has_ground_x()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(18, this->ground_x(), output); - } - - // optional float ground_y = 19; - if (has_ground_y()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(19, this->ground_y(), output); - } - - // optional float ground_z = 20; - if (has_ground_z()) { - ::google::protobuf::internal::WireFormatLite::WriteFloat(20, this->ground_z(), output); - } - - // repeated float camera_matrix = 21; - for (int i = 0; i < this->camera_matrix_size(); i++) { - ::google::protobuf::internal::WireFormatLite::WriteFloat( - 21, this->camera_matrix(i), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* RGBDImage::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required .px.HeaderInfo header = 1; - if (has_header()) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteMessageNoVirtualToArray( - 1, this->header(), target); - } - - // required uint32 cols = 2; - if (has_cols()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(2, this->cols(), target); - } - - // required uint32 rows = 3; - if (has_rows()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(3, this->rows(), target); - } - - // required uint32 step1 = 4; - if (has_step1()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(4, this->step1(), target); - } - - // required uint32 type1 = 5; - if (has_type1()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(5, this->type1(), target); - } - - // required bytes imageData1 = 6; - if (has_imagedata1()) { - target = - ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 6, this->imagedata1(), target); - } - - // required uint32 step2 = 7; - if (has_step2()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(7, this->step2(), target); - } - - // required uint32 type2 = 8; - if (has_type2()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(8, this->type2(), target); - } - - // required bytes imageData2 = 9; - if (has_imagedata2()) { - target = - ::google::protobuf::internal::WireFormatLite::WriteBytesToArray( - 9, this->imagedata2(), target); - } - - // optional uint32 camera_config = 10; - if (has_camera_config()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(10, this->camera_config(), target); - } - - // optional uint32 camera_type = 11; - if (has_camera_type()) { - target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(11, this->camera_type(), target); - } - - // optional float roll = 12; - if (has_roll()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(12, this->roll(), target); - } - - // optional float pitch = 13; - if (has_pitch()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(13, this->pitch(), target); - } - - // optional float yaw = 14; - if (has_yaw()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(14, this->yaw(), target); - } - - // optional float lon = 15; - if (has_lon()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(15, this->lon(), target); - } - - // optional float lat = 16; - if (has_lat()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(16, this->lat(), target); - } - - // optional float alt = 17; - if (has_alt()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(17, this->alt(), target); - } - - // optional float ground_x = 18; - if (has_ground_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(18, this->ground_x(), target); - } - - // optional float ground_y = 19; - if (has_ground_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(19, this->ground_y(), target); - } - - // optional float ground_z = 20; - if (has_ground_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(20, this->ground_z(), target); - } - - // repeated float camera_matrix = 21; - for (int i = 0; i < this->camera_matrix_size(); i++) { - target = ::google::protobuf::internal::WireFormatLite:: - WriteFloatToArray(21, this->camera_matrix(i), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int RGBDImage::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required .px.HeaderInfo header = 1; - if (has_header()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual( - this->header()); - } - - // required uint32 cols = 2; - if (has_cols()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->cols()); - } - - // required uint32 rows = 3; - if (has_rows()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->rows()); - } - - // required uint32 step1 = 4; - if (has_step1()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->step1()); - } - - // required uint32 type1 = 5; - if (has_type1()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->type1()); - } - - // required bytes imageData1 = 6; - if (has_imagedata1()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::BytesSize( - this->imagedata1()); - } - - // required uint32 step2 = 7; - if (has_step2()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->step2()); - } - - // required uint32 type2 = 8; - if (has_type2()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->type2()); - } - - } - if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) { - // required bytes imageData2 = 9; - if (has_imagedata2()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::BytesSize( - this->imagedata2()); - } - - // optional uint32 camera_config = 10; - if (has_camera_config()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->camera_config()); - } - - // optional uint32 camera_type = 11; - if (has_camera_type()) { - total_size += 1 + - ::google::protobuf::internal::WireFormatLite::UInt32Size( - this->camera_type()); - } - - // optional float roll = 12; - if (has_roll()) { - total_size += 1 + 4; - } - - // optional float pitch = 13; - if (has_pitch()) { - total_size += 1 + 4; - } - - // optional float yaw = 14; - if (has_yaw()) { - total_size += 1 + 4; - } - - // optional float lon = 15; - if (has_lon()) { - total_size += 1 + 4; - } - - // optional float lat = 16; - if (has_lat()) { - total_size += 2 + 4; - } - - } - if (_has_bits_[16 / 32] & (0xffu << (16 % 32))) { - // optional float alt = 17; - if (has_alt()) { - total_size += 2 + 4; - } - - // optional float ground_x = 18; - if (has_ground_x()) { - total_size += 2 + 4; - } - - // optional float ground_y = 19; - if (has_ground_y()) { - total_size += 2 + 4; - } - - // optional float ground_z = 20; - if (has_ground_z()) { - total_size += 2 + 4; - } - - } - // repeated float camera_matrix = 21; - { - int data_size = 0; - data_size = 4 * this->camera_matrix_size(); - total_size += 2 * this->camera_matrix_size() + data_size; - } - - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void RGBDImage::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const RGBDImage* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void RGBDImage::MergeFrom(const RGBDImage& from) { - GOOGLE_CHECK_NE(&from, this); - camera_matrix_.MergeFrom(from.camera_matrix_); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_header()) { - mutable_header()->::px::HeaderInfo::MergeFrom(from.header()); - } - if (from.has_cols()) { - set_cols(from.cols()); - } - if (from.has_rows()) { - set_rows(from.rows()); - } - if (from.has_step1()) { - set_step1(from.step1()); - } - if (from.has_type1()) { - set_type1(from.type1()); - } - if (from.has_imagedata1()) { - set_imagedata1(from.imagedata1()); - } - if (from.has_step2()) { - set_step2(from.step2()); - } - if (from.has_type2()) { - set_type2(from.type2()); - } - } - if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) { - if (from.has_imagedata2()) { - set_imagedata2(from.imagedata2()); - } - if (from.has_camera_config()) { - set_camera_config(from.camera_config()); - } - if (from.has_camera_type()) { - set_camera_type(from.camera_type()); - } - if (from.has_roll()) { - set_roll(from.roll()); - } - if (from.has_pitch()) { - set_pitch(from.pitch()); - } - if (from.has_yaw()) { - set_yaw(from.yaw()); - } - if (from.has_lon()) { - set_lon(from.lon()); - } - if (from.has_lat()) { - set_lat(from.lat()); - } - } - if (from._has_bits_[16 / 32] & (0xffu << (16 % 32))) { - if (from.has_alt()) { - set_alt(from.alt()); - } - if (from.has_ground_x()) { - set_ground_x(from.ground_x()); - } - if (from.has_ground_y()) { - set_ground_y(from.ground_y()); - } - if (from.has_ground_z()) { - set_ground_z(from.ground_z()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void RGBDImage::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void RGBDImage::CopyFrom(const RGBDImage& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool RGBDImage::IsInitialized() const { - if ((_has_bits_[0] & 0x000001ff) != 0x000001ff) return false; - - if (has_header()) { - if (!this->header().IsInitialized()) return false; - } - return true; -} - -void RGBDImage::Swap(RGBDImage* other) { - if (other != this) { - std::swap(header_, other->header_); - std::swap(cols_, other->cols_); - std::swap(rows_, other->rows_); - std::swap(step1_, other->step1_); - std::swap(type1_, other->type1_); - std::swap(imagedata1_, other->imagedata1_); - std::swap(step2_, other->step2_); - std::swap(type2_, other->type2_); - std::swap(imagedata2_, other->imagedata2_); - std::swap(camera_config_, other->camera_config_); - std::swap(camera_type_, other->camera_type_); - std::swap(roll_, other->roll_); - std::swap(pitch_, other->pitch_); - std::swap(yaw_, other->yaw_); - std::swap(lon_, other->lon_); - std::swap(lat_, other->lat_); - std::swap(alt_, other->alt_); - std::swap(ground_x_, other->ground_x_); - std::swap(ground_y_, other->ground_y_); - std::swap(ground_z_, other->ground_z_); - camera_matrix_.Swap(&other->camera_matrix_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata RGBDImage::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = RGBDImage_descriptor_; - metadata.reflection = RGBDImage_reflection_; - return metadata; -} - - -// =================================================================== - -#ifndef _MSC_VER -const int Waypoint::kXFieldNumber; -const int Waypoint::kYFieldNumber; -const int Waypoint::kZFieldNumber; -const int Waypoint::kRollFieldNumber; -const int Waypoint::kPitchFieldNumber; -const int Waypoint::kYawFieldNumber; -#endif // !_MSC_VER - -Waypoint::Waypoint() - : ::google::protobuf::Message() { - SharedCtor(); -} - -void Waypoint::InitAsDefaultInstance() { -} - -Waypoint::Waypoint(const Waypoint& from) - : ::google::protobuf::Message() { - SharedCtor(); - MergeFrom(from); -} - -void Waypoint::SharedCtor() { - _cached_size_ = 0; - x_ = 0; - y_ = 0; - z_ = 0; - roll_ = 0; - pitch_ = 0; - yaw_ = 0; - ::memset(_has_bits_, 0, sizeof(_has_bits_)); -} - -Waypoint::~Waypoint() { - SharedDtor(); -} - -void Waypoint::SharedDtor() { - if (this != default_instance_) { - } -} - -void Waypoint::SetCachedSize(int size) const { - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); -} -const ::google::protobuf::Descriptor* Waypoint::descriptor() { - protobuf_AssignDescriptorsOnce(); - return Waypoint_descriptor_; -} - -const Waypoint& Waypoint::default_instance() { - if (default_instance_ == NULL) protobuf_AddDesc_pixhawk_2eproto(); return *default_instance_; -} - -Waypoint* Waypoint::default_instance_ = NULL; - -Waypoint* Waypoint::New() const { - return new Waypoint; -} - -void Waypoint::Clear() { - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - x_ = 0; - y_ = 0; - z_ = 0; - roll_ = 0; - pitch_ = 0; - yaw_ = 0; - } - ::memset(_has_bits_, 0, sizeof(_has_bits_)); - mutable_unknown_fields()->Clear(); -} - -bool Waypoint::MergePartialFromCodedStream( - ::google::protobuf::io::CodedInputStream* input) { -#define DO_(EXPRESSION) if (!(EXPRESSION)) return false - ::google::protobuf::uint32 tag; - while ((tag = input->ReadTag()) != 0) { - switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) { - // required double x = 1; - case 1: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &x_))); - set_has_x(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(17)) goto parse_y; - break; - } - - // required double y = 2; - case 2: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_y: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &y_))); - set_has_y(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(25)) goto parse_z; - break; - } - - // optional double z = 3; - case 3: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_z: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &z_))); - set_has_z(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(33)) goto parse_roll; - break; - } - - // optional double roll = 4; - case 4: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_roll: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &roll_))); - set_has_roll(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(41)) goto parse_pitch; - break; - } - - // optional double pitch = 5; - case 5: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_pitch: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &pitch_))); - set_has_pitch(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectTag(49)) goto parse_yaw; - break; - } - - // optional double yaw = 6; - case 6: { - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED64) { - parse_yaw: - DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive< - double, ::google::protobuf::internal::WireFormatLite::TYPE_DOUBLE>( - input, &yaw_))); - set_has_yaw(); - } else { - goto handle_uninterpreted; - } - if (input->ExpectAtEnd()) return true; - break; - } - - default: { - handle_uninterpreted: - if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) == - ::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) { - return true; - } - DO_(::google::protobuf::internal::WireFormat::SkipField( - input, tag, mutable_unknown_fields())); - break; - } - } - } - return true; -#undef DO_ -} - -void Waypoint::SerializeWithCachedSizes( - ::google::protobuf::io::CodedOutputStream* output) const { - // required double x = 1; - if (has_x()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(1, this->x(), output); - } - - // required double y = 2; - if (has_y()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(2, this->y(), output); - } - - // optional double z = 3; - if (has_z()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(3, this->z(), output); - } - - // optional double roll = 4; - if (has_roll()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(4, this->roll(), output); - } - - // optional double pitch = 5; - if (has_pitch()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(5, this->pitch(), output); - } - - // optional double yaw = 6; - if (has_yaw()) { - ::google::protobuf::internal::WireFormatLite::WriteDouble(6, this->yaw(), output); - } - - if (!unknown_fields().empty()) { - ::google::protobuf::internal::WireFormat::SerializeUnknownFields( - unknown_fields(), output); - } -} - -::google::protobuf::uint8* Waypoint::SerializeWithCachedSizesToArray( - ::google::protobuf::uint8* target) const { - // required double x = 1; - if (has_x()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(1, this->x(), target); - } - - // required double y = 2; - if (has_y()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(2, this->y(), target); - } - - // optional double z = 3; - if (has_z()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(3, this->z(), target); - } - - // optional double roll = 4; - if (has_roll()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(4, this->roll(), target); - } - - // optional double pitch = 5; - if (has_pitch()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(5, this->pitch(), target); - } - - // optional double yaw = 6; - if (has_yaw()) { - target = ::google::protobuf::internal::WireFormatLite::WriteDoubleToArray(6, this->yaw(), target); - } - - if (!unknown_fields().empty()) { - target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray( - unknown_fields(), target); - } - return target; -} - -int Waypoint::ByteSize() const { - int total_size = 0; - - if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) { - // required double x = 1; - if (has_x()) { - total_size += 1 + 8; - } - - // required double y = 2; - if (has_y()) { - total_size += 1 + 8; - } - - // optional double z = 3; - if (has_z()) { - total_size += 1 + 8; - } - - // optional double roll = 4; - if (has_roll()) { - total_size += 1 + 8; - } - - // optional double pitch = 5; - if (has_pitch()) { - total_size += 1 + 8; - } - - // optional double yaw = 6; - if (has_yaw()) { - total_size += 1 + 8; - } - - } - if (!unknown_fields().empty()) { - total_size += - ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize( - unknown_fields()); - } - GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN(); - _cached_size_ = total_size; - GOOGLE_SAFE_CONCURRENT_WRITES_END(); - return total_size; -} - -void Waypoint::MergeFrom(const ::google::protobuf::Message& from) { - GOOGLE_CHECK_NE(&from, this); - const Waypoint* source = - ::google::protobuf::internal::dynamic_cast_if_available( - &from); - if (source == NULL) { - ::google::protobuf::internal::ReflectionOps::Merge(from, this); - } else { - MergeFrom(*source); - } -} - -void Waypoint::MergeFrom(const Waypoint& from) { - GOOGLE_CHECK_NE(&from, this); - if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) { - if (from.has_x()) { - set_x(from.x()); - } - if (from.has_y()) { - set_y(from.y()); - } - if (from.has_z()) { - set_z(from.z()); - } - if (from.has_roll()) { - set_roll(from.roll()); - } - if (from.has_pitch()) { - set_pitch(from.pitch()); - } - if (from.has_yaw()) { - set_yaw(from.yaw()); - } - } - mutable_unknown_fields()->MergeFrom(from.unknown_fields()); -} - -void Waypoint::CopyFrom(const ::google::protobuf::Message& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -void Waypoint::CopyFrom(const Waypoint& from) { - if (&from == this) return; - Clear(); - MergeFrom(from); -} - -bool Waypoint::IsInitialized() const { - if ((_has_bits_[0] & 0x00000003) != 0x00000003) return false; - - return true; -} - -void Waypoint::Swap(Waypoint* other) { - if (other != this) { - std::swap(x_, other->x_); - std::swap(y_, other->y_); - std::swap(z_, other->z_); - std::swap(roll_, other->roll_); - std::swap(pitch_, other->pitch_); - std::swap(yaw_, other->yaw_); - std::swap(_has_bits_[0], other->_has_bits_[0]); - _unknown_fields_.Swap(&other->_unknown_fields_); - std::swap(_cached_size_, other->_cached_size_); - } -} - -::google::protobuf::Metadata Waypoint::GetMetadata() const { - protobuf_AssignDescriptorsOnce(); - ::google::protobuf::Metadata metadata; - metadata.descriptor = Waypoint_descriptor_; - metadata.reflection = Waypoint_reflection_; - return metadata; -} - - -// @@protoc_insertion_point(namespace_scope) - -} // namespace px - -// @@protoc_insertion_point(global_scope) diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore deleted file mode 100644 index 7c98650cc..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/.gitignore +++ /dev/null @@ -1,3 +0,0 @@ -/testmav0.9 -/testmav1.0 -/testmav1.0_nonstrict diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c b/mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c deleted file mode 100644 index 2fd7fa378..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/test/posix/testmav.c +++ /dev/null @@ -1,159 +0,0 @@ -/* - simple MAVLink testsuite for C - */ -#include -#include -#include -#include -#include - -#define MAVLINK_USE_CONVENIENCE_FUNCTIONS -#define MAVLINK_COMM_NUM_BUFFERS 2 - -// this trick allows us to make mavlink_message_t as small as possible -// for this dialect, which saves some memory -#include -#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE - -#include -static mavlink_system_t mavlink_system = {42,11,}; - -#define MAVLINK_ASSERT(x) assert(x) -static void comm_send_ch(mavlink_channel_t chan, uint8_t c); - -static mavlink_message_t last_msg; - -#include -#include - -static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]; - -static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS; -static unsigned error_count; - -static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO; - -static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx) -{ -#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def) - switch (f->type) { - case MAVLINK_TYPE_CHAR: - printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_UINT8_T: - printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_INT8_T: - printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_UINT16_T: - printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2)); - break; - case MAVLINK_TYPE_INT16_T: - printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2)); - break; - case MAVLINK_TYPE_UINT32_T: - printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_INT32_T: - printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_UINT64_T: - printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8)); - break; - case MAVLINK_TYPE_INT64_T: - printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8)); - break; - case MAVLINK_TYPE_FLOAT: - printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_DOUBLE: - printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8)); - break; - } -} - -static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f) -{ - printf("%s: ", f->name); - if (f->array_length == 0) { - print_one_field(msg, f, 0); - printf(" "); - } else { - unsigned i; - /* print an array */ - if (f->type == MAVLINK_TYPE_CHAR) { - printf("'%.*s'", f->array_length, - f->wire_offset+(const char *)_MAV_PAYLOAD(msg)); - - } else { - printf("[ "); - for (i=0; iarray_length; i++) { - print_one_field(msg, f, i); - if (i < f->array_length) { - printf(", "); - } - } - printf("]"); - } - } - printf(" "); -} - -static void print_message(mavlink_message_t *msg) -{ - const mavlink_message_info_t *m = &message_info[msg->msgid]; - const mavlink_field_info_t *f = m->fields; - unsigned i; - printf("%s { ", m->name); - for (i=0; inum_fields; i++) { - print_field(msg, &f[i]); - } - printf("}\n"); -} - -static void comm_send_ch(mavlink_channel_t chan, uint8_t c) -{ - mavlink_status_t status; - if (mavlink_parse_char(chan, c, &last_msg, &status)) { - print_message(&last_msg); - chan_counts[chan]++; - /* channel 0 gets 3 messages per message, because of - the channel defaults for _pack() and _encode() */ - if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) { - printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n", - chan_counts[chan], status.current_rx_seq); - error_count++; - } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) { - printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n", - (unsigned)chan, chan_counts[chan], status.current_rx_seq); - error_count++; - } - if (message_lengths[last_msg.msgid] != last_msg.len) { - printf("Incorrect message length %u for message %u - expected %u\n", - (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]); - error_count++; - } - } - if (status.packet_rx_drop_count != 0) { - printf("Parse error at packet %u\n", chan_counts[chan]); - error_count++; - } -} - -int main(void) -{ - mavlink_channel_t chan; - mavlink_test_all(11, 10, &last_msg); - for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) { - printf("Received %u messages on channel %u OK\n", - chan_counts[chan], (unsigned)chan); - } - if (error_count != 0) { - printf("Error count %u\n", error_count); - exit(1); - } - printf("No errors detected\n"); - return 0; -} - diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp deleted file mode 100644 index 98b4abf05..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.cpp +++ /dev/null @@ -1,8 +0,0 @@ -// stdafx.cpp : source file that includes just the standard includes -// testmav.pch will be the pre-compiled header -// stdafx.obj will contain the pre-compiled type information - -#include "stdafx.h" - -// TODO: reference any additional headers you need in STDAFX.H -// and not in this file diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h deleted file mode 100644 index 47a0d0252..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/stdafx.h +++ /dev/null @@ -1,15 +0,0 @@ -// stdafx.h : include file for standard system include files, -// or project specific include files that are used frequently, but -// are changed infrequently -// - -#pragma once - -#include "targetver.h" - -#include -#include - - - -// TODO: reference additional headers your program requires here diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h deleted file mode 100644 index 90e767bfc..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/targetver.h +++ /dev/null @@ -1,8 +0,0 @@ -#pragma once - -// Including SDKDDKVer.h defines the highest available Windows platform. - -// If you wish to build your application for a previous Windows platform, include WinSDKVer.h and -// set the _WIN32_WINNT macro to the platform you wish to support before including SDKDDKVer.h. - -#include diff --git a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp b/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp deleted file mode 100644 index aa83caced..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/C/test/windows/testmav.cpp +++ /dev/null @@ -1,154 +0,0 @@ -// testmav.cpp : Defines the entry point for the console application. -// - -#include "stdafx.h" -#include "stdio.h" -#include "stdint.h" -#include "stddef.h" -#include "assert.h" - - -#define MAVLINK_USE_CONVENIENCE_FUNCTIONS -#define MAVLINK_COMM_NUM_BUFFERS 2 - -#include -static mavlink_system_t mavlink_system = {42,11,}; - -#define MAVLINK_ASSERT(x) assert(x) -static void comm_send_ch(mavlink_channel_t chan, uint8_t c); - -static mavlink_message_t last_msg; - -#include -#include - -static unsigned chan_counts[MAVLINK_COMM_NUM_BUFFERS]; - -static const unsigned message_lengths[] = MAVLINK_MESSAGE_LENGTHS; -static unsigned error_count; - -static const mavlink_message_info_t message_info[256] = MAVLINK_MESSAGE_INFO; - -static void print_one_field(mavlink_message_t *msg, const mavlink_field_info_t *f, int idx) -{ -#define PRINT_FORMAT(f, def) (f->print_format?f->print_format:def) - switch (f->type) { - case MAVLINK_TYPE_CHAR: - printf(PRINT_FORMAT(f, "%c"), _MAV_RETURN_char(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_UINT8_T: - printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint8_t(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_INT8_T: - printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int8_t(msg, f->wire_offset+idx*1)); - break; - case MAVLINK_TYPE_UINT16_T: - printf(PRINT_FORMAT(f, "%u"), _MAV_RETURN_uint16_t(msg, f->wire_offset+idx*2)); - break; - case MAVLINK_TYPE_INT16_T: - printf(PRINT_FORMAT(f, "%d"), _MAV_RETURN_int16_t(msg, f->wire_offset+idx*2)); - break; - case MAVLINK_TYPE_UINT32_T: - printf(PRINT_FORMAT(f, "%lu"), (unsigned long)_MAV_RETURN_uint32_t(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_INT32_T: - printf(PRINT_FORMAT(f, "%ld"), (long)_MAV_RETURN_int32_t(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_UINT64_T: - printf(PRINT_FORMAT(f, "%llu"), (unsigned long long)_MAV_RETURN_uint64_t(msg, f->wire_offset+idx*8)); - break; - case MAVLINK_TYPE_INT64_T: - printf(PRINT_FORMAT(f, "%lld"), (long long)_MAV_RETURN_int64_t(msg, f->wire_offset+idx*8)); - break; - case MAVLINK_TYPE_FLOAT: - printf(PRINT_FORMAT(f, "%f"), (double)_MAV_RETURN_float(msg, f->wire_offset+idx*4)); - break; - case MAVLINK_TYPE_DOUBLE: - printf(PRINT_FORMAT(f, "%f"), _MAV_RETURN_double(msg, f->wire_offset+idx*8)); - break; - } -} - -static void print_field(mavlink_message_t *msg, const mavlink_field_info_t *f) -{ - printf("%s: ", f->name); - if (f->array_length == 0) { - print_one_field(msg, f, 0); - printf(" "); - } else { - unsigned i; - /* print an array */ - if (f->type == MAVLINK_TYPE_CHAR) { - printf("'%.*s'", f->array_length, - f->wire_offset+(const char *)_MAV_PAYLOAD(msg)); - - } else { - printf("[ "); - for (i=0; iarray_length; i++) { - print_one_field(msg, f, i); - if (i < f->array_length) { - printf(", "); - } - } - printf("]"); - } - } - printf(" "); -} - -static void print_message(mavlink_message_t *msg) -{ - const mavlink_message_info_t *m = &message_info[msg->msgid]; - const mavlink_field_info_t *f = m->fields; - unsigned i; - printf("%s { ", m->name); - for (i=0; inum_fields; i++) { - print_field(msg, &f[i]); - } - printf("}\n"); -} - -static void comm_send_ch(mavlink_channel_t chan, uint8_t c) -{ - mavlink_status_t status; - if (mavlink_parse_char(chan, c, &last_msg, &status)) { - print_message(&last_msg); - chan_counts[chan]++; - /* channel 0 gets 3 messages per message, because of - the channel defaults for _pack() and _encode() */ - if (chan == MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)(chan_counts[chan]*3)) { - printf("Channel 0 sequence mismatch error at packet %u (rx_seq=%u)\n", - chan_counts[chan], status.current_rx_seq); - error_count++; - } else if (chan > MAVLINK_COMM_0 && status.current_rx_seq != (uint8_t)chan_counts[chan]) { - printf("Channel %u sequence mismatch error at packet %u (rx_seq=%u)\n", - (unsigned)chan, chan_counts[chan], status.current_rx_seq); - error_count++; - } - if (message_lengths[last_msg.msgid] != last_msg.len) { - printf("Incorrect message length %u for message %u - expected %u\n", - (unsigned)last_msg.len, (unsigned)last_msg.msgid, message_lengths[last_msg.msgid]); - error_count++; - } - } - if (status.packet_rx_drop_count != 0) { - printf("Parse error at packet %u\n", chan_counts[chan]); - error_count++; - } -} - -int _tmain(int argc, _TCHAR* argv[]) -{ - int chan; - mavlink_test_all(11, 10, &last_msg); - for (chan=MAVLINK_COMM_0; chan<=MAVLINK_COMM_1; chan++) { - printf("Received %u messages on channel %u OK\n", - chan_counts[chan], (unsigned)chan); - } - if (error_count != 0) { - printf("Error count %u\n", error_count); - return(1); - } - printf("No errors detected\n"); - return 0; -} diff --git a/mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py b/mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py deleted file mode 100644 index 165c1b343..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/gen_MatrixPilot.py +++ /dev/null @@ -1,93 +0,0 @@ -#!/usr/bin/env python -''' -Use mavgen.py matrixpilot.xml definitions to generate -C and Python MAVLink routines for sending and parsing the protocol -This python script is soley for MatrixPilot MAVLink impoementation - -Copyright Pete Hollands 2011 -Released under GNU GPL version 3 or later -''' - -import os, sys, glob, re -from shutil import copy -from mavgen import mavgen - -# allow import from the parent directory, where mavutil.py is -# Under Windows, this script must be run from a DOS command window -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -class options: - """ a class to simulate the options of mavgen OptionsParser""" - def __init__(self, lang, output, wire_protocol): - self.language = lang - self.wire_protocol = wire_protocol - self.output = output - -def remove_include_files(target_directory): - search_pattern = target_directory+'/*.h' - print "search pattern is", search_pattern - files_to_remove = glob.glob(search_pattern) - for afile in files_to_remove : - try: - print "removing", afile - os.remove(afile) - except: - print "error while trying to remove", afile - -def copy_include_files(source_directory,target_directory): - search_pattern = source_directory+'/*.h' - files_to_copy = glob.glob(search_pattern) - for afile in files_to_copy: - basename = os.path.basename(afile) - print "Copying ...", basename - copy(afile, target_directory) - -protocol = "1.0" - -xml_directory = './message_definitions/v'+protocol -print "xml_directory is", xml_directory -xml_file_names = [] -xml_file_names.append(xml_directory+"/"+"matrixpilot.xml") - -for xml_file in xml_file_names: - print "xml file is ", xml_file - opts = options(lang = "C", output = "C/include_v"+protocol, \ - wire_protocol=protocol) - args = [] - args.append(xml_file) - mavgen(opts, args) - xml_file_base = os.path.basename(xml_file) - xml_file_base = re.sub("\.xml","", xml_file_base) - print "xml_file_base is", xml_file_base - opts = options(lang = "python", \ - output="python/mavlink_"+xml_file_base+"_v"+protocol+".py", \ - wire_protocol=protocol) - mavgen(opts,args) - -mavlink_directory_list = ["common","matrixpilot"] -for mavlink_directory in mavlink_directory_list : - # Look specifically for MatrixPilot directory structure - target_directory = "../../../../MAVLink/include/"+mavlink_directory - source_directory = "C/include_v"+protocol+"/"+mavlink_directory - if os.access(source_directory, os.R_OK): - if os.access(target_directory, os.W_OK): - print "Preparing to copy over files..." - print "About to remove all files in",target_directory - print "OK to continue ?[Yes / No]: ", - line = sys.stdin.readline() - if line == "Yes\n" or line == "yes\n" \ - or line == "Y\n" or line == "y\n": - print "passed" - remove_include_files(target_directory) - copy_include_files(source_directory,target_directory) - print "Finished copying over include files" - else : - print "Your answer is No. Exiting Program" - sys.exit() - else : - print "Cannot find " + target_directory + "in MatrixPilot" - sys.exit() - else: - print "Could not find files to copy at", source_directory - print "Exiting Program." - sys.exit() diff --git a/mavlink/share/pyshared/pymavlink/generator/gen_all.py b/mavlink/share/pyshared/pymavlink/generator/gen_all.py deleted file mode 100644 index 5b24f85cb..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/gen_all.py +++ /dev/null @@ -1,44 +0,0 @@ -#!/usr/bin/env python - -''' -Use mavgen.py on all available MAVLink XML definitions to generate -C and Python MAVLink routines for sending and parsing the protocol - -Copyright Pete Hollands 2011 -Released under GNU GPL version 3 or later -''' - -import os, sys, glob, re -from mavgen import mavgen - -# allow import from the parent directory, where mavutil.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -class options: - """ a class to simulate the options of mavgen OptionsParser""" - def __init__(self, lang, output, wire_protocol): - self.language = lang - self.wire_protocol = wire_protocol - self.output = output - -protocols = [ '0.9', '1.0' ] - -for protocol in protocols : - xml_directory = './message_definitions/v'+protocol - print "xml_directory is", xml_directory - xml_file_names = glob.glob(xml_directory+'/*.xml') - - for xml_file in xml_file_names: - print "xml file is ", xml_file - opts = options(lang = "C", output = "C/include_v"+protocol, \ - wire_protocol=protocol) - args = [] - args.append(xml_file) - mavgen(opts, args) - xml_file_base = os.path.basename(xml_file) - xml_file_base = re.sub("\.xml","", xml_file_base) - print "xml_file_base is", xml_file_base - opts = options(lang = "python", \ - output="python/mavlink_"+xml_file_base+"_v"+protocol+".py", \ - wire_protocol=protocol) - mavgen(opts,args) diff --git a/mavlink/share/pyshared/pymavlink/generator/gen_all.sh b/mavlink/share/pyshared/pymavlink/generator/gen_all.sh deleted file mode 100644 index e8dafedc5..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/gen_all.sh +++ /dev/null @@ -1,12 +0,0 @@ -#!/bin/sh - -for protocol in 0.9 1.0; do - for xml in message_definitions/v$protocol/*.xml; do - base=$(basename $xml .xml) - ./mavgen.py --lang=C --wire-protocol=$protocol --output=C/include_v$protocol $xml || exit 1 - ./mavgen.py --lang=python --wire-protocol=$protocol --output=python/mavlink_${base}_v$protocol.py $xml || exit 1 - done -done - -cp -f python/mavlink_ardupilotmega_v0.9.py ../mavlink.py -cp -f python/mavlink_ardupilotmega_v1.0.py ../mavlinkv10.py diff --git a/mavlink/share/pyshared/pymavlink/generator/mavgen.py b/mavlink/share/pyshared/pymavlink/generator/mavgen.py deleted file mode 100644 index 05f71f778..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/mavgen.py +++ /dev/null @@ -1,82 +0,0 @@ -#!/usr/bin/env python -''' -parse a MAVLink protocol XML file and generate a python implementation - -Copyright Andrew Tridgell 2011 -Released under GNU GPL version 3 or later -''' - -def mavgen(opts, args) : - """Generate mavlink message formatters and parsers (C and Python ) using options - and args where args are a list of xml files. This function allows python - scripts under Windows to control mavgen using the same interface as - shell scripts under Unix""" - import sys, textwrap, os - - import mavparse - import mavgen_python - import mavgen_c - - xml = [] - - for fname in args: - print("Parsing %s" % fname) - xml.append(mavparse.MAVXML(fname, opts.wire_protocol)) - - # expand includes - for x in xml[:]: - for i in x.include: - fname = os.path.join(os.path.dirname(x.filename), i) - print("Parsing %s" % fname) - xml.append(mavparse.MAVXML(fname, opts.wire_protocol)) - - # include message lengths and CRCs too - for idx in range(0, 256): - if x.message_lengths[idx] == 0: - x.message_lengths[idx] = xml[-1].message_lengths[idx] - x.message_crcs[idx] = xml[-1].message_crcs[idx] - x.message_names[idx] = xml[-1].message_names[idx] - - # work out max payload size across all includes - largest_payload = 0 - for x in xml: - if x.largest_payload > largest_payload: - largest_payload = x.largest_payload - for x in xml: - x.largest_payload = largest_payload - - if mavparse.check_duplicates(xml): - sys.exit(1) - - print("Found %u MAVLink message types in %u XML files" % ( - mavparse.total_msgs(xml), len(xml))) - - if opts.language == 'python': - mavgen_python.generate(opts.output, xml) - elif opts.language == 'C': - mavgen_c.generate(opts.output, xml) - else: - print("Unsupported language %s" % opts.language) - - -if __name__=="__main__": - import sys, textwrap, os - - from optparse import OptionParser - - # allow import from the parent directory, where mavutil.py is - sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - - import mavparse - import mavgen_python - import mavgen_c - - parser = OptionParser("%prog [options] ") - parser.add_option("-o", "--output", dest="output", default="mavlink", help="output directory.") - parser.add_option("--lang", dest="language", default="python", help="language of generated code: 'Python' or 'C' [default: %default]") - parser.add_option("--wire-protocol", dest="wire_protocol", default=mavparse.PROTOCOL_0_9, help="MAVLink protocol version: '0.9' or '1.0'. [default: %default]") - (opts, args) = parser.parse_args() - - if len(args) < 1: - parser.error("You must supply at least one MAVLink XML protocol definition") - mavgen(opts, args) diff --git a/mavlink/share/pyshared/pymavlink/generator/mavgen_c.py b/mavlink/share/pyshared/pymavlink/generator/mavgen_c.py deleted file mode 100644 index 255919f0d..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/mavgen_c.py +++ /dev/null @@ -1,581 +0,0 @@ -#!/usr/bin/env python -''' -parse a MAVLink protocol XML file and generate a C implementation - -Copyright Andrew Tridgell 2011 -Released under GNU GPL version 3 or later -''' - -import sys, textwrap, os, time -import mavparse, mavtemplate - -t = mavtemplate.MAVTemplate() - -def generate_version_h(directory, xml): - '''generate version.h''' - f = open(os.path.join(directory, "version.h"), mode='w') - t.write(f,''' -/** @file - * @brief MAVLink comm protocol built from ${basename}.xml - * @see http://pixhawk.ethz.ch/software/mavlink - */ -#ifndef MAVLINK_VERSION_H -#define MAVLINK_VERSION_H - -#define MAVLINK_BUILD_DATE "${parse_time}" -#define MAVLINK_WIRE_PROTOCOL_VERSION "${wire_protocol_version}" -#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE ${largest_payload} - -#endif // MAVLINK_VERSION_H -''', xml) - f.close() - -def generate_mavlink_h(directory, xml): - '''generate mavlink.h''' - f = open(os.path.join(directory, "mavlink.h"), mode='w') - t.write(f,''' -/** @file - * @brief MAVLink comm protocol built from ${basename}.xml - * @see http://pixhawk.ethz.ch/software/mavlink - */ -#ifndef MAVLINK_H -#define MAVLINK_H - -#ifndef MAVLINK_STX -#define MAVLINK_STX ${protocol_marker} -#endif - -#ifndef MAVLINK_ENDIAN -#define MAVLINK_ENDIAN ${mavlink_endian} -#endif - -#ifndef MAVLINK_ALIGNED_FIELDS -#define MAVLINK_ALIGNED_FIELDS ${aligned_fields_define} -#endif - -#ifndef MAVLINK_CRC_EXTRA -#define MAVLINK_CRC_EXTRA ${crc_extra_define} -#endif - -#include "version.h" -#include "${basename}.h" - -#endif // MAVLINK_H -''', xml) - f.close() - -def generate_main_h(directory, xml): - '''generate main header per XML file''' - f = open(os.path.join(directory, xml.basename + ".h"), mode='w') - t.write(f, ''' -/** @file - * @brief MAVLink comm protocol generated from ${basename}.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef ${basename_upper}_H -#define ${basename_upper}_H - -#ifdef __cplusplus -extern "C" { -#endif - -// MESSAGE LENGTHS AND CRCS - -#ifndef MAVLINK_MESSAGE_LENGTHS -#define MAVLINK_MESSAGE_LENGTHS {${message_lengths_array}} -#endif - -#ifndef MAVLINK_MESSAGE_CRCS -#define MAVLINK_MESSAGE_CRCS {${message_crcs_array}} -#endif - -#ifndef MAVLINK_MESSAGE_INFO -#define MAVLINK_MESSAGE_INFO {${message_info_array}} -#endif - -#include "../protocol.h" - -#define MAVLINK_ENABLED_${basename_upper} - -${{include_list:#include "../${base}/${base}.h" -}} - -// MAVLINK VERSION - -#ifndef MAVLINK_VERSION -#define MAVLINK_VERSION ${version} -#endif - -#if (MAVLINK_VERSION == 0) -#undef MAVLINK_VERSION -#define MAVLINK_VERSION ${version} -#endif - -// ENUM DEFINITIONS - -${{enum: -/** @brief ${description} */ -#ifndef HAVE_ENUM_${name} -#define HAVE_ENUM_${name} -enum ${name} -{ -${{entry: ${name}=${value}, /* ${description} |${{param:${description}| }} */ -}} -}; -#endif -}} - -// MESSAGE DEFINITIONS -${{message:#include "./mavlink_msg_${name_lower}.h" -}} - -#ifdef __cplusplus -} -#endif // __cplusplus -#endif // ${basename_upper}_H -''', xml) - - f.close() - - -def generate_message_h(directory, m): - '''generate per-message header for a XML file''' - f = open(os.path.join(directory, 'mavlink_msg_%s.h' % m.name_lower), mode='w') - t.write(f, ''' -// MESSAGE ${name} PACKING - -#define MAVLINK_MSG_ID_${name} ${id} - -typedef struct __mavlink_${name_lower}_t -{ -${{ordered_fields: ${type} ${name}${array_suffix}; ///< ${description} -}} -} mavlink_${name_lower}_t; - -#define MAVLINK_MSG_ID_${name}_LEN ${wire_length} -#define MAVLINK_MSG_ID_${id}_LEN ${wire_length} - -${{array_fields:#define MAVLINK_MSG_${msg_name}_FIELD_${name_upper}_LEN ${array_length} -}} - -#define MAVLINK_MESSAGE_INFO_${name} { \\ - "${name}", \\ - ${num_fields}, \\ - { ${{ordered_fields: { "${name}", ${c_print_format}, MAVLINK_TYPE_${type_upper}, ${array_length}, ${wire_offset}, offsetof(mavlink_${name_lower}_t, ${name}) }, \\ - }} } \\ -} - - -/** - * @brief Pack a ${name_lower} message - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * -${{arg_fields: * @param ${name} ${description} -}} - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_${name_lower}_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, - ${{arg_fields: ${array_const}${type} ${array_prefix}${name},}}) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[${wire_length}]; -${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname}); -}} -${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); -}} - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, ${wire_length}); -#else - mavlink_${name_lower}_t packet; -${{scalar_fields: packet.${name} = ${putname}; -}} -${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length}); -}} - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, ${wire_length}); -#endif - - msg->msgid = MAVLINK_MSG_ID_${name}; - return mavlink_finalize_message(msg, system_id, component_id, ${wire_length}${crc_extra_arg}); -} - -/** - * @brief Pack a ${name_lower} message on a channel - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param chan The MAVLink channel this message was sent over - * @param msg The MAVLink message to compress the data into -${{arg_fields: * @param ${name} ${description} -}} - * @return length of the message in bytes (excluding serial stream start sign) - */ -static inline uint16_t mavlink_msg_${name_lower}_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, - mavlink_message_t* msg, - ${{arg_fields:${array_const}${type} ${array_prefix}${name},}}) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[${wire_length}]; -${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname}); -}} -${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); -}} - memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, ${wire_length}); -#else - mavlink_${name_lower}_t packet; -${{scalar_fields: packet.${name} = ${putname}; -}} -${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length}); -}} - memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, ${wire_length}); -#endif - - msg->msgid = MAVLINK_MSG_ID_${name}; - return mavlink_finalize_message_chan(msg, system_id, component_id, chan, ${wire_length}${crc_extra_arg}); -} - -/** - * @brief Encode a ${name_lower} struct into a message - * - * @param system_id ID of this system - * @param component_id ID of this component (e.g. 200 for IMU) - * @param msg The MAVLink message to compress the data into - * @param ${name_lower} C-struct to read the message contents from - */ -static inline uint16_t mavlink_msg_${name_lower}_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_${name_lower}_t* ${name_lower}) -{ - return mavlink_msg_${name_lower}_pack(system_id, component_id, msg,${{arg_fields: ${name_lower}->${name},}}); -} - -/** - * @brief Send a ${name_lower} message - * @param chan MAVLink channel to send the message - * -${{arg_fields: * @param ${name} ${description} -}} - */ -#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS - -static inline void mavlink_msg_${name_lower}_send(mavlink_channel_t chan,${{arg_fields: ${array_const}${type} ${array_prefix}${name},}}) -{ -#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS - char buf[${wire_length}]; -${{scalar_fields: _mav_put_${type}(buf, ${wire_offset}, ${putname}); -}} -${{array_fields: _mav_put_${type}_array(buf, ${wire_offset}, ${name}, ${array_length}); -}} - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, buf, ${wire_length}${crc_extra_arg}); -#else - mavlink_${name_lower}_t packet; -${{scalar_fields: packet.${name} = ${putname}; -}} -${{array_fields: mav_array_memcpy(packet.${name}, ${name}, sizeof(${type})*${array_length}); -}} - _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_${name}, (const char *)&packet, ${wire_length}${crc_extra_arg}); -#endif -} - -#endif - -// MESSAGE ${name} UNPACKING - -${{fields: -/** - * @brief Get field ${name} from ${name_lower} message - * - * @return ${description} - */ -static inline ${return_type} mavlink_msg_${name_lower}_get_${name}(const mavlink_message_t* msg${get_arg}) -{ - return _MAV_RETURN_${type}${array_tag}(msg, ${array_return_arg} ${wire_offset}); -} -}} - -/** - * @brief Decode a ${name_lower} message into a struct - * - * @param msg The message to decode - * @param ${name_lower} C-struct to decode the message contents into - */ -static inline void mavlink_msg_${name_lower}_decode(const mavlink_message_t* msg, mavlink_${name_lower}_t* ${name_lower}) -{ -#if MAVLINK_NEED_BYTE_SWAP -${{ordered_fields: ${decode_left}mavlink_msg_${name_lower}_get_${name}(msg${decode_right}); -}} -#else - memcpy(${name_lower}, _MAV_PAYLOAD(msg), ${wire_length}); -#endif -} -''', m) - f.close() - - -def generate_testsuite_h(directory, xml): - '''generate testsuite.h per XML file''' - f = open(os.path.join(directory, "testsuite.h"), mode='w') - t.write(f, ''' -/** @file - * @brief MAVLink comm protocol testsuite generated from ${basename}.xml - * @see http://qgroundcontrol.org/mavlink/ - */ -#ifndef ${basename_upper}_TESTSUITE_H -#define ${basename_upper}_TESTSUITE_H - -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef MAVLINK_TEST_ALL -#define MAVLINK_TEST_ALL -${{include_list:static void mavlink_test_${base}(uint8_t, uint8_t, mavlink_message_t *last_msg); -}} -static void mavlink_test_${basename}(uint8_t, uint8_t, mavlink_message_t *last_msg); - -static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ -${{include_list: mavlink_test_${base}(system_id, component_id, last_msg); -}} - mavlink_test_${basename}(system_id, component_id, last_msg); -} -#endif - -${{include_list:#include "../${base}/testsuite.h" -}} - -${{message: -static void mavlink_test_${name_lower}(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg) -{ - mavlink_message_t msg; - uint8_t buffer[MAVLINK_MAX_PACKET_LEN]; - uint16_t i; - mavlink_${name_lower}_t packet_in = { - ${{ordered_fields:${c_test_value}, - }}}; - mavlink_${name_lower}_t packet1, packet2; - memset(&packet1, 0, sizeof(packet1)); - ${{scalar_fields: packet1.${name} = packet_in.${name}; - }} - ${{array_fields: mav_array_memcpy(packet1.${name}, packet_in.${name}, sizeof(${type})*${array_length}); - }} - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_${name_lower}_encode(system_id, component_id, &msg, &packet1); - mavlink_msg_${name_lower}_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_${name_lower}_pack(system_id, component_id, &msg ${{arg_fields:, packet1.${name} }}); - mavlink_msg_${name_lower}_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_${name_lower}_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg ${{arg_fields:, packet1.${name} }}); - mavlink_msg_${name_lower}_decode(&msg, &packet2); - MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0); - - memset(&packet2, 0, sizeof(packet2)); - mavlink_msg_to_send_buffer(buffer, &msg); - for (i=0; i= 1 and self.buf[0] != ${protocol_marker}: - magic = self.buf[0] - self.buf = self.buf[1:] - if self.robust_parsing: - m = MAVLink_bad_data(chr(magic), "Bad prefix") - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - self.expected_length = 6 - self.total_receive_errors += 1 - return m - if self.have_prefix_error: - return None - self.have_prefix_error = True - self.total_receive_errors += 1 - raise MAVError("invalid MAVLink prefix '%s'" % magic) - self.have_prefix_error = False - if len(self.buf) >= 2: - (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) - self.expected_length += 8 - if self.expected_length >= 8 and len(self.buf) >= self.expected_length: - mbuf = self.buf[0:self.expected_length] - self.buf = self.buf[self.expected_length:] - self.expected_length = 6 - if self.robust_parsing: - try: - m = self.decode(mbuf) - self.total_packets_received += 1 - except MAVError as reason: - m = MAVLink_bad_data(mbuf, reason.message) - self.total_receive_errors += 1 - else: - m = self.decode(mbuf) - self.total_packets_received += 1 - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - return m - return None - - def parse_buffer(self, s): - '''input some data bytes, possibly returning a list of new messages''' - m = self.parse_char(s) - if m is None: - return None - ret = [m] - while True: - m = self.parse_char("") - if m is None: - return ret - ret.append(m) - return ret - - def decode(self, msgbuf): - '''decode a buffer as a MAVLink message''' - # decode the header - try: - magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) - except struct.error as emsg: - raise MAVError('Unable to unpack MAVLink header: %s' % emsg) - if ord(magic) != ${protocol_marker}: - raise MAVError("invalid MAVLink prefix '%s'" % magic) - if mlen != len(msgbuf)-8: - raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) - - if not msgId in mavlink_map: - raise MAVError('unknown MAVLink message ID %u' % msgId) - - # decode the payload - (fmt, type, order_map, crc_extra) = mavlink_map[msgId] - - # decode the checksum - try: - crc, = struct.unpack(' self.enum[-1].highest_value): - self.enum[-1].highest_value = value - self.enum[-1].entry.append(MAVEnumEntry(attrs['name'], value)) - elif in_element == "mavlink.enums.enum.entry.param": - check_attrs(attrs, ['index'], 'enum param') - self.enum[-1].entry[-1].param.append(MAVEnumParam(attrs['index'])) - - def end_element(name): - in_element = '.'.join(in_element_list) - if in_element == "mavlink.enums.enum": - # add a ENUM_END - self.enum[-1].entry.append(MAVEnumEntry("%s_ENUM_END" % self.enum[-1].name, - self.enum[-1].highest_value+1, end_marker=True)) - in_element_list.pop() - - def char_data(data): - in_element = '.'.join(in_element_list) - if in_element == "mavlink.messages.message.description": - self.message[-1].description += data - elif in_element == "mavlink.messages.message.field": - self.message[-1].fields[-1].description += data - elif in_element == "mavlink.enums.enum.description": - self.enum[-1].description += data - elif in_element == "mavlink.enums.enum.entry.description": - self.enum[-1].entry[-1].description += data - elif in_element == "mavlink.enums.enum.entry.param": - self.enum[-1].entry[-1].param[-1].description += data - elif in_element == "mavlink.version": - self.version = int(data) - elif in_element == "mavlink.include": - self.include.append(data) - - f = open(filename, mode='rb') - p = xml.parsers.expat.ParserCreate() - p.StartElementHandler = start_element - p.EndElementHandler = end_element - p.CharacterDataHandler = char_data - p.ParseFile(f) - f.close() - - self.message_lengths = [ 0 ] * 256 - self.message_crcs = [ 0 ] * 256 - self.message_names = [ None ] * 256 - self.largest_payload = 0 - - for m in self.message: - m.wire_length = 0 - m.fieldnames = [] - m.ordered_fieldnames = [] - if self.sort_fields: - m.ordered_fields = sorted(m.fields, - key=operator.attrgetter('type_length'), - reverse=True) - else: - m.ordered_fields = m.fields - for f in m.fields: - m.fieldnames.append(f.name) - for f in m.ordered_fields: - f.wire_offset = m.wire_length - m.wire_length += f.wire_length - m.ordered_fieldnames.append(f.name) - f.set_test_value() - m.num_fields = len(m.fieldnames) - if m.num_fields > 64: - raise MAVParseError("num_fields=%u : Maximum number of field names allowed is" % ( - m.num_fields, 64)) - m.crc_extra = message_checksum(m) - self.message_lengths[m.id] = m.wire_length - self.message_names[m.id] = m.name - self.message_crcs[m.id] = m.crc_extra - if m.wire_length > self.largest_payload: - self.largest_payload = m.wire_length - - if m.wire_length+8 > 64: - print("Note: message %s is longer than 64 bytes long (%u bytes), which can cause fragmentation since many radio modems use 64 bytes as maximum air transfer unit." % (m.name, m.wire_length+8)) - - def __str__(self): - return "MAVXML for %s from %s (%u message, %u enums)" % ( - self.basename, self.filename, len(self.message), len(self.enum)) - - -def message_checksum(msg): - '''calculate a 8-bit checksum of the key fields of a message, so we - can detect incompatible XML changes''' - crc = mavutil.x25crc(msg.name + ' ') - for f in msg.ordered_fields: - crc.accumulate(f.type + ' ') - crc.accumulate(f.name + ' ') - if f.array_length: - crc.accumulate(chr(f.array_length)) - return (crc.crc&0xFF) ^ (crc.crc>>8) - -def merge_enums(xml): - '''merge enums between XML files''' - emap = {} - for x in xml: - newenums = [] - for enum in x.enum: - if enum.name in emap: - emap[enum.name].entry.pop() # remove end marker - emap[enum.name].entry.extend(enum.entry) - print("Merged enum %s" % enum.name) - else: - newenums.append(enum) - emap[enum.name] = enum - x.enum = newenums - # sort by value - for e in emap: - emap[e].entry = sorted(emap[e].entry, - key=operator.attrgetter('value'), - reverse=False) - - -def check_duplicates(xml): - '''check for duplicate message IDs''' - - merge_enums(xml) - - msgmap = {} - enummap = {} - for x in xml: - for m in x.message: - if m.id in msgmap: - print("ERROR: Duplicate message id %u for %s (%s:%u) also used by %s" % ( - m.id, m.name, - x.filename, m.linenumber, - msgmap[m.id])) - return True - fieldset = set() - for f in m.fields: - if f.name in fieldset: - print("ERROR: Duplicate field %s in message %s (%s:%u)" % ( - f.name, m.name, - x.filename, m.linenumber)) - return True - fieldset.add(f.name) - msgmap[m.id] = '%s (%s:%u)' % (m.name, x.filename, m.linenumber) - for enum in x.enum: - for entry in enum.entry: - s1 = "%s.%s" % (enum.name, entry.name) - s2 = "%s.%s" % (enum.name, entry.value) - if s1 in enummap or s2 in enummap: - print("ERROR: Duplicate enums %s/%s at %s:%u and %s" % ( - s1, entry.value, x.filename, enum.linenumber, - enummap.get(s1) or enummap.get(s2))) - return True - enummap[s1] = "%s:%u" % (x.filename, enum.linenumber) - enummap[s2] = "%s:%u" % (x.filename, enum.linenumber) - - return False - - - -def total_msgs(xml): - '''count total number of msgs''' - count = 0 - for x in xml: - count += len(x.message) - return count - -def mkdir_p(dir): - try: - os.makedirs(dir) - except OSError as exc: - if exc.errno == errno.EEXIST: - pass - else: raise - -# check version consistent -# add test.xml -# finish test suite -# printf style error macro, if defined call errors diff --git a/mavlink/share/pyshared/pymavlink/generator/mavtemplate.py b/mavlink/share/pyshared/pymavlink/generator/mavtemplate.py deleted file mode 100644 index 6ef015315..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/mavtemplate.py +++ /dev/null @@ -1,121 +0,0 @@ -#!/usr/bin/env python -''' -simple templating system for mavlink generator - -Copyright Andrew Tridgell 2011 -Released under GNU GPL version 3 or later -''' - -from mavparse import MAVParseError - -class MAVTemplate(object): - '''simple templating system''' - def __init__(self, - start_var_token="${", - end_var_token="}", - start_rep_token="${{", - end_rep_token="}}", - trim_leading_lf=True, - checkmissing=True): - self.start_var_token = start_var_token - self.end_var_token = end_var_token - self.start_rep_token = start_rep_token - self.end_rep_token = end_rep_token - self.trim_leading_lf = trim_leading_lf - self.checkmissing = checkmissing - - def find_end(self, text, start_token, end_token): - '''find the of a token. - Returns the offset in the string immediately after the matching end_token''' - if not text.startswith(start_token): - raise MAVParseError("invalid token start") - offset = len(start_token) - nesting = 1 - while nesting > 0: - idx1 = text[offset:].find(start_token) - idx2 = text[offset:].find(end_token) - if idx1 == -1 and idx2 == -1: - raise MAVParseError("token nesting error") - if idx1 == -1 or idx1 > idx2: - offset += idx2 + len(end_token) - nesting -= 1 - else: - offset += idx1 + len(start_token) - nesting += 1 - return offset - - def find_var_end(self, text): - '''find the of a variable''' - return self.find_end(text, self.start_var_token, self.end_var_token) - - def find_rep_end(self, text): - '''find the of a repitition''' - return self.find_end(text, self.start_rep_token, self.end_rep_token) - - def substitute(self, text, subvars={}, - trim_leading_lf=None, checkmissing=None): - '''substitute variables in a string''' - - if trim_leading_lf is None: - trim_leading_lf = self.trim_leading_lf - if checkmissing is None: - checkmissing = self.checkmissing - - # handle repititions - while True: - subidx = text.find(self.start_rep_token) - if subidx == -1: - break - endidx = self.find_rep_end(text[subidx:]) - if endidx == -1: - raise MAVParseError("missing end macro in %s" % text[subidx:]) - part1 = text[0:subidx] - part2 = text[subidx+len(self.start_rep_token):subidx+(endidx-len(self.end_rep_token))] - part3 = text[subidx+endidx:] - a = part2.split(':') - field_name = a[0] - rest = ':'.join(a[1:]) - v = getattr(subvars, field_name, None) - if v is None: - raise MAVParseError('unable to find field %s' % field_name) - t1 = part1 - for f in v: - t1 += self.substitute(rest, f, trim_leading_lf=False, checkmissing=False) - if len(v) != 0 and t1[-1] in ["\n", ","]: - t1 = t1[:-1] - t1 += part3 - text = t1 - - if trim_leading_lf: - if text[0] == '\n': - text = text[1:] - while True: - idx = text.find(self.start_var_token) - if idx == -1: - return text - endidx = text[idx:].find(self.end_var_token) - if endidx == -1: - raise MAVParseError('missing end of variable: %s' % text[idx:idx+10]) - varname = text[idx+2:idx+endidx] - if isinstance(subvars, dict): - if not varname in subvars: - if checkmissing: - raise MAVParseError("unknown variable in '%s%s%s'" % ( - self.start_var_token, varname, self.end_var_token)) - return text[0:idx+endidx] + self.substitute(text[idx+endidx:], subvars, - trim_leading_lf=False, checkmissing=False) - value = subvars[varname] - else: - value = getattr(subvars, varname, None) - if value is None: - if checkmissing: - raise MAVParseError("unknown variable in '%s%s%s'" % ( - self.start_var_token, varname, self.end_var_token)) - return text[0:idx+endidx] + self.substitute(text[idx+endidx:], subvars, - trim_leading_lf=False, checkmissing=False) - text = text.replace("%s%s%s" % (self.start_var_token, varname, self.end_var_token), str(value)) - return text - - def write(self, file, text, subvars={}, trim_leading_lf=True): - '''write to a file with variable substitution''' - file.write(self.substitute(text, subvars=subvars, trim_leading_lf=trim_leading_lf)) diff --git a/mavlink/share/pyshared/pymavlink/generator/mavtestgen.py b/mavlink/share/pyshared/pymavlink/generator/mavtestgen.py deleted file mode 100644 index faffa1c19..000000000 --- a/mavlink/share/pyshared/pymavlink/generator/mavtestgen.py +++ /dev/null @@ -1,142 +0,0 @@ -#!/usr/bin/env python -''' -generate a MAVLink test suite - -Copyright Andrew Tridgell 2011 -Released under GNU GPL version 3 or later -''' - -import sys, textwrap -from optparse import OptionParser - -# mavparse is up a directory level -sys.path.append('..') -import mavparse - -def gen_value(f, i, language): - '''generate a test value for the ith field of a message''' - type = f.type - - # could be an array - if type.find("[") != -1: - aidx = type.find("[") - basetype = type[0:aidx] - if basetype == "array": - basetype = "int8_t" - if language == 'C': - return '(const %s *)"%s%u"' % (basetype, f.name, i) - return '"%s%u"' % (f.name, i) - - if type == 'float': - return 17.0 + i*7 - if type == 'char': - return 'A' + i - if type == 'int8_t': - return 5 + i - if type in ['int8_t', 'uint8_t']: - return 5 + i - if type in ['uint8_t_mavlink_version']: - return 2 - if type in ['int16_t', 'uint16_t']: - return 17235 + i*52 - if type in ['int32_t', 'uint32_t']: - v = 963497464 + i*52 - if language == 'C': - return "%sL" % v - return v - if type in ['int64_t', 'uint64_t']: - v = 9223372036854775807 + i*63 - if language == 'C': - return "%sLL" % v - return v - - - -def generate_methods_python(outf, msgs): - outf.write(""" -''' -MAVLink protocol test implementation (auto-generated by mavtestgen.py) - -Generated from: %s - -Note: this file has been auto-generated. DO NOT EDIT -''' - -import mavlink - -def generate_outputs(mav): - '''generate all message types as outputs''' -""") - for m in msgs: - if m.name == "HEARTBEAT": continue - outf.write("\tmav.%s_send(" % m.name.lower()) - for i in range(0, len(m.fields)): - f = m.fields[i] - outf.write("%s=%s" % (f.name, gen_value(f, i, 'py'))) - if i != len(m.fields)-1: - outf.write(",") - outf.write(")\n") - - -def generate_methods_C(outf, msgs): - outf.write(""" -/* -MAVLink protocol test implementation (auto-generated by mavtestgen.py) - -Generated from: %s - -Note: this file has been auto-generated. DO NOT EDIT -*/ - -static void mavtest_generate_outputs(mavlink_channel_t chan) -{ -""") - for m in msgs: - if m.name == "HEARTBEAT": continue - outf.write("\tmavlink_msg_%s_send(chan," % m.name.lower()) - for i in range(0, len(m.fields)): - f = m.fields[i] - outf.write("%s" % gen_value(f, i, 'C')) - if i != len(m.fields)-1: - outf.write(",") - outf.write(");\n") - outf.write("}\n") - - - -###################################################################### -'''main program''' - -parser = OptionParser("%prog [options] ") -parser.add_option("-o", "--output", dest="output", default="mavtest", help="output folder [default: %default]") -(opts, args) = parser.parse_args() - -if len(args) < 1: - parser.error("You must supply at least one MAVLink XML protocol definition") - - -msgs = [] -enums = [] - -for fname in args: - (m, e) = mavparse.parse_mavlink_xml(fname) - msgs.extend(m) - enums.extend(e) - - -if mavparse.check_duplicates(msgs): - sys.exit(1) - -print("Found %u MAVLink message types" % len(msgs)) - -print("Generating python %s" % (opts.output+'.py')) -outf = open(opts.output + '.py', "w") -generate_methods_python(outf, msgs) -outf.close() - -print("Generating C %s" % (opts.output+'.h')) -outf = open(opts.output + '.h', "w") -generate_methods_C(outf, msgs) -outf.close() - -print("Generated %s OK" % opts.output) diff --git a/mavlink/share/pyshared/pymavlink/mavextra.py b/mavlink/share/pyshared/pymavlink/mavextra.py deleted file mode 100644 index 5395f6036..000000000 --- a/mavlink/share/pyshared/pymavlink/mavextra.py +++ /dev/null @@ -1,154 +0,0 @@ -#!/usr/bin/env python -''' -useful extra functions for use by mavlink clients - -Copyright Andrew Tridgell 2011 -Released under GNU GPL version 3 or later -''' - -from math import * - - -def kmh(mps): - '''convert m/s to Km/h''' - return mps*3.6 - -def altitude(press_abs, ground_press=955.0, ground_temp=30): - '''calculate barometric altitude''' - return log(ground_press/press_abs)*(ground_temp+273.15)*29271.267*0.001 - - -def mag_heading(RAW_IMU, ATTITUDE, declination=0, SENSOR_OFFSETS=None, ofs=None): - '''calculate heading from raw magnetometer''' - mag_x = RAW_IMU.xmag - mag_y = RAW_IMU.ymag - mag_z = RAW_IMU.zmag - if SENSOR_OFFSETS is not None and ofs is not None: - mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x - mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y - mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z - - headX = mag_x*cos(ATTITUDE.pitch) + mag_y*sin(ATTITUDE.roll)*sin(ATTITUDE.pitch) + mag_z*cos(ATTITUDE.roll)*sin(ATTITUDE.pitch) - headY = mag_y*cos(ATTITUDE.roll) - mag_z*sin(ATTITUDE.roll) - heading = degrees(atan2(-headY,headX)) + declination - if heading < 0: - heading += 360 - return heading - -def mag_field(RAW_IMU, SENSOR_OFFSETS=None, ofs=None): - '''calculate magnetic field strength from raw magnetometer''' - mag_x = RAW_IMU.xmag - mag_y = RAW_IMU.ymag - mag_z = RAW_IMU.zmag - if SENSOR_OFFSETS is not None and ofs is not None: - mag_x += ofs[0] - SENSOR_OFFSETS.mag_ofs_x - mag_y += ofs[1] - SENSOR_OFFSETS.mag_ofs_y - mag_z += ofs[2] - SENSOR_OFFSETS.mag_ofs_z - return sqrt(mag_x**2 + mag_y**2 + mag_z**2) - -def angle_diff(angle1, angle2): - '''show the difference between two angles in degrees''' - ret = angle1 - angle2 - if ret > 180: - ret -= 360; - if ret < -180: - ret += 360 - return ret - - -lowpass_data = {} - -def lowpass(var, key, factor): - '''a simple lowpass filter''' - global lowpass_data - if not key in lowpass_data: - lowpass_data[key] = var - else: - lowpass_data[key] = factor*lowpass_data[key] + (1.0 - factor)*var - return lowpass_data[key] - -last_delta = {} - -def delta(var, key): - '''calculate slope''' - global last_delta - dv = 0 - if key in last_delta: - dv = var - last_delta[key] - last_delta[key] = var - return dv - -def delta_angle(var, key): - '''calculate slope of an angle''' - global last_delta - dv = 0 - if key in last_delta: - dv = var - last_delta[key] - last_delta[key] = var - if dv > 180: - dv -= 360 - if dv < -180: - dv += 360 - return dv - -def roll_estimate(RAW_IMU,smooth=0.7): - '''estimate roll from accelerometer''' - rx = lowpass(RAW_IMU.xacc,'rx',smooth) - ry = lowpass(RAW_IMU.yacc,'ry',smooth) - rz = lowpass(RAW_IMU.zacc,'rz',smooth) - return degrees(-asin(ry/sqrt(rx**2+ry**2+rz**2))) - -def pitch_estimate(RAW_IMU, smooth=0.7): - '''estimate pitch from accelerometer''' - rx = lowpass(RAW_IMU.xacc,'rx',smooth) - ry = lowpass(RAW_IMU.yacc,'ry',smooth) - rz = lowpass(RAW_IMU.zacc,'rz',smooth) - return degrees(asin(rx/sqrt(rx**2+ry**2+rz**2))) - -def gravity(RAW_IMU, SENSOR_OFFSETS=None, ofs=None, smooth=0.7): - '''estimate pitch from accelerometer''' - rx = RAW_IMU.xacc - ry = RAW_IMU.yacc - rz = RAW_IMU.zacc+45 - if SENSOR_OFFSETS is not None and ofs is not None: - rx += ofs[0] - SENSOR_OFFSETS.accel_cal_x - ry += ofs[1] - SENSOR_OFFSETS.accel_cal_y - rz += ofs[2] - SENSOR_OFFSETS.accel_cal_z - return lowpass(sqrt(rx**2+ry**2+rz**2)*0.01,'_gravity',smooth) - - - -def pitch_sim(SIMSTATE, GPS_RAW): - '''estimate pitch from SIMSTATE accels''' - xacc = SIMSTATE.xacc - lowpass(delta(GPS_RAW.v,"v")*6.6, "v", 0.9) - zacc = SIMSTATE.zacc - zacc += SIMSTATE.ygyro * GPS_RAW.v; - if xacc/zacc >= 1: - return 0 - if xacc/zacc <= -1: - return -0 - return degrees(-asin(xacc/zacc)) - -def distance_two(GPS_RAW1, GPS_RAW2): - '''distance between two points''' - lat1 = radians(GPS_RAW1.lat) - lat2 = radians(GPS_RAW2.lat) - lon1 = radians(GPS_RAW1.lon) - lon2 = radians(GPS_RAW2.lon) - dLat = lat2 - lat1 - dLon = lon2 - lon1 - - a = sin(0.5*dLat) * sin(0.5*dLat) + sin(0.5*dLon) * sin(0.5*dLon) * cos(lat1) * cos(lat2) - c = 2.0 * atan2(sqrt(a), sqrt(1.0-a)) - return 6371 * 1000 * c - - -first_fix = None - -def distance_home(GPS_RAW): - '''distance from first fix point''' - global first_fix - if first_fix == None or first_fix.fix_type < 2: - first_fix = GPS_RAW - return 0 - return distance_two(GPS_RAW, first_fix) diff --git a/mavlink/share/pyshared/pymavlink/mavlink.py b/mavlink/share/pyshared/pymavlink/mavlink.py deleted file mode 100644 index 3287a921d..000000000 --- a/mavlink/share/pyshared/pymavlink/mavlink.py +++ /dev/null @@ -1,4930 +0,0 @@ -''' -MAVLink protocol implementation (auto-generated by mavgen.py) - -Generated from: ardupilotmega.xml,common.xml - -Note: this file has been auto-generated. DO NOT EDIT -''' - -import struct, array, mavutil, time - -WIRE_PROTOCOL_VERSION = "0.9" - -class MAVLink_header(object): - '''MAVLink message header''' - def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): - self.mlen = mlen - self.seq = seq - self.srcSystem = srcSystem - self.srcComponent = srcComponent - self.msgId = msgId - - def pack(self): - return struct.pack('BBBBBB', 85, self.mlen, self.seq, - self.srcSystem, self.srcComponent, self.msgId) - -class MAVLink_message(object): - '''base MAVLink message class''' - def __init__(self, msgId, name): - self._header = MAVLink_header(msgId) - self._payload = None - self._msgbuf = None - self._crc = None - self._fieldnames = [] - self._type = name - - def get_msgbuf(self): - return self._msgbuf - - def get_header(self): - return self._header - - def get_payload(self): - return self._payload - - def get_crc(self): - return self._crc - - def get_fieldnames(self): - return self._fieldnames - - def get_type(self): - return self._type - - def get_msgId(self): - return self._header.msgId - - def get_srcSystem(self): - return self._header.srcSystem - - def get_srcComponent(self): - return self._header.srcComponent - - def get_seq(self): - return self._header.seq - - def __str__(self): - ret = '%s {' % self._type - for a in self._fieldnames: - v = getattr(self, a) - ret += '%s : %s, ' % (a, v) - ret = ret[0:-2] + '}' - return ret - - def pack(self, mav, crc_extra, payload): - self._payload = payload - self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, - mav.srcSystem, mav.srcComponent) - self._msgbuf = self._header.pack() + payload - crc = mavutil.x25crc(self._msgbuf[1:]) - if False: # using CRC extra - crc.accumulate(chr(crc_extra)) - self._crc = crc.crc - self._msgbuf += struct.pack('hhhfiiffffff', self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z, self.mag_declination, self.raw_press, self.raw_temp, self.gyro_cal_x, self.gyro_cal_y, self.gyro_cal_z, self.accel_cal_x, self.accel_cal_y, self.accel_cal_z)) - -class MAVLink_set_mag_offsets_message(MAVLink_message): - ''' - set the magnetometer offsets - ''' - def __init__(self, target_system, target_component, mag_ofs_x, mag_ofs_y, mag_ofs_z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MAG_OFFSETS, 'SET_MAG_OFFSETS') - self._fieldnames = ['target_system', 'target_component', 'mag_ofs_x', 'mag_ofs_y', 'mag_ofs_z'] - self.target_system = target_system - self.target_component = target_component - self.mag_ofs_x = mag_ofs_x - self.mag_ofs_y = mag_ofs_y - self.mag_ofs_z = mag_ofs_z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 29, struct.pack('>BBhhh', self.target_system, self.target_component, self.mag_ofs_x, self.mag_ofs_y, self.mag_ofs_z)) - -class MAVLink_meminfo_message(MAVLink_message): - ''' - state of APM memory - ''' - def __init__(self, brkval, freemem): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MEMINFO, 'MEMINFO') - self._fieldnames = ['brkval', 'freemem'] - self.brkval = brkval - self.freemem = freemem - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 208, struct.pack('>HH', self.brkval, self.freemem)) - -class MAVLink_ap_adc_message(MAVLink_message): - ''' - raw ADC output - ''' - def __init__(self, adc1, adc2, adc3, adc4, adc5, adc6): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_AP_ADC, 'AP_ADC') - self._fieldnames = ['adc1', 'adc2', 'adc3', 'adc4', 'adc5', 'adc6'] - self.adc1 = adc1 - self.adc2 = adc2 - self.adc3 = adc3 - self.adc4 = adc4 - self.adc5 = adc5 - self.adc6 = adc6 - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 188, struct.pack('>HHHHHH', self.adc1, self.adc2, self.adc3, self.adc4, self.adc5, self.adc6)) - -class MAVLink_digicam_configure_message(MAVLink_message): - ''' - Configure on-board Camera Control System. - ''' - def __init__(self, target_system, target_component, mode, shutter_speed, aperture, iso, exposure_type, command_id, engine_cut_off, extra_param, extra_value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, 'DIGICAM_CONFIGURE') - self._fieldnames = ['target_system', 'target_component', 'mode', 'shutter_speed', 'aperture', 'iso', 'exposure_type', 'command_id', 'engine_cut_off', 'extra_param', 'extra_value'] - self.target_system = target_system - self.target_component = target_component - self.mode = mode - self.shutter_speed = shutter_speed - self.aperture = aperture - self.iso = iso - self.exposure_type = exposure_type - self.command_id = command_id - self.engine_cut_off = engine_cut_off - self.extra_param = extra_param - self.extra_value = extra_value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 118, struct.pack('>BBBHBBBBBBf', self.target_system, self.target_component, self.mode, self.shutter_speed, self.aperture, self.iso, self.exposure_type, self.command_id, self.engine_cut_off, self.extra_param, self.extra_value)) - -class MAVLink_digicam_control_message(MAVLink_message): - ''' - Control on-board Camera Control System to take shots. - ''' - def __init__(self, target_system, target_component, session, zoom_pos, zoom_step, focus_lock, shot, command_id, extra_param, extra_value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_DIGICAM_CONTROL, 'DIGICAM_CONTROL') - self._fieldnames = ['target_system', 'target_component', 'session', 'zoom_pos', 'zoom_step', 'focus_lock', 'shot', 'command_id', 'extra_param', 'extra_value'] - self.target_system = target_system - self.target_component = target_component - self.session = session - self.zoom_pos = zoom_pos - self.zoom_step = zoom_step - self.focus_lock = focus_lock - self.shot = shot - self.command_id = command_id - self.extra_param = extra_param - self.extra_value = extra_value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 242, struct.pack('>BBBBbBBBBf', self.target_system, self.target_component, self.session, self.zoom_pos, self.zoom_step, self.focus_lock, self.shot, self.command_id, self.extra_param, self.extra_value)) - -class MAVLink_mount_configure_message(MAVLink_message): - ''' - Message to configure a camera mount, directional antenna, etc. - ''' - def __init__(self, target_system, target_component, mount_mode, stab_roll, stab_pitch, stab_yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_CONFIGURE, 'MOUNT_CONFIGURE') - self._fieldnames = ['target_system', 'target_component', 'mount_mode', 'stab_roll', 'stab_pitch', 'stab_yaw'] - self.target_system = target_system - self.target_component = target_component - self.mount_mode = mount_mode - self.stab_roll = stab_roll - self.stab_pitch = stab_pitch - self.stab_yaw = stab_yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 19, struct.pack('>BBBBBB', self.target_system, self.target_component, self.mount_mode, self.stab_roll, self.stab_pitch, self.stab_yaw)) - -class MAVLink_mount_control_message(MAVLink_message): - ''' - Message to control a camera mount, directional antenna, etc. - ''' - def __init__(self, target_system, target_component, input_a, input_b, input_c, save_position): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_CONTROL, 'MOUNT_CONTROL') - self._fieldnames = ['target_system', 'target_component', 'input_a', 'input_b', 'input_c', 'save_position'] - self.target_system = target_system - self.target_component = target_component - self.input_a = input_a - self.input_b = input_b - self.input_c = input_c - self.save_position = save_position - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 97, struct.pack('>BBiiiB', self.target_system, self.target_component, self.input_a, self.input_b, self.input_c, self.save_position)) - -class MAVLink_mount_status_message(MAVLink_message): - ''' - Message with some status from APM to GCS about camera or - antenna mount - ''' - def __init__(self, target_system, target_component, pointing_a, pointing_b, pointing_c): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MOUNT_STATUS, 'MOUNT_STATUS') - self._fieldnames = ['target_system', 'target_component', 'pointing_a', 'pointing_b', 'pointing_c'] - self.target_system = target_system - self.target_component = target_component - self.pointing_a = pointing_a - self.pointing_b = pointing_b - self.pointing_c = pointing_c - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 233, struct.pack('>BBiii', self.target_system, self.target_component, self.pointing_a, self.pointing_b, self.pointing_c)) - -class MAVLink_fence_point_message(MAVLink_message): - ''' - A fence point. Used to set a point when from GCS - -> MAV. Also used to return a point from MAV -> GCS - ''' - def __init__(self, target_system, target_component, idx, count, lat, lng): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_POINT, 'FENCE_POINT') - self._fieldnames = ['target_system', 'target_component', 'idx', 'count', 'lat', 'lng'] - self.target_system = target_system - self.target_component = target_component - self.idx = idx - self.count = count - self.lat = lat - self.lng = lng - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 18, struct.pack('>BBBBff', self.target_system, self.target_component, self.idx, self.count, self.lat, self.lng)) - -class MAVLink_fence_fetch_point_message(MAVLink_message): - ''' - Request a current fence point from MAV - ''' - def __init__(self, target_system, target_component, idx): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_FETCH_POINT, 'FENCE_FETCH_POINT') - self._fieldnames = ['target_system', 'target_component', 'idx'] - self.target_system = target_system - self.target_component = target_component - self.idx = idx - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 68, struct.pack('>BBB', self.target_system, self.target_component, self.idx)) - -class MAVLink_fence_status_message(MAVLink_message): - ''' - Status of geo-fencing. Sent in extended status - stream when fencing enabled - ''' - def __init__(self, breach_status, breach_count, breach_type, breach_time): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_STATUS, 'FENCE_STATUS') - self._fieldnames = ['breach_status', 'breach_count', 'breach_type', 'breach_time'] - self.breach_status = breach_status - self.breach_count = breach_count - self.breach_type = breach_type - self.breach_time = breach_time - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 136, struct.pack('>BHBI', self.breach_status, self.breach_count, self.breach_type, self.breach_time)) - -class MAVLink_ahrs_message(MAVLink_message): - ''' - Status of DCM attitude estimator - ''' - def __init__(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_AHRS, 'AHRS') - self._fieldnames = ['omegaIx', 'omegaIy', 'omegaIz', 'accel_weight', 'renorm_val', 'error_rp', 'error_yaw'] - self.omegaIx = omegaIx - self.omegaIy = omegaIy - self.omegaIz = omegaIz - self.accel_weight = accel_weight - self.renorm_val = renorm_val - self.error_rp = error_rp - self.error_yaw = error_yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 127, struct.pack('>fffffff', self.omegaIx, self.omegaIy, self.omegaIz, self.accel_weight, self.renorm_val, self.error_rp, self.error_yaw)) - -class MAVLink_simstate_message(MAVLink_message): - ''' - Status of simulation environment, if used - ''' - def __init__(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SIMSTATE, 'SIMSTATE') - self._fieldnames = ['roll', 'pitch', 'yaw', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro'] - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.xacc = xacc - self.yacc = yacc - self.zacc = zacc - self.xgyro = xgyro - self.ygyro = ygyro - self.zgyro = zgyro - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 42, struct.pack('>fffffffff', self.roll, self.pitch, self.yaw, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro)) - -class MAVLink_hwstatus_message(MAVLink_message): - ''' - Status of key hardware - ''' - def __init__(self, Vcc, I2Cerr): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_HWSTATUS, 'HWSTATUS') - self._fieldnames = ['Vcc', 'I2Cerr'] - self.Vcc = Vcc - self.I2Cerr = I2Cerr - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 21, struct.pack('>HB', self.Vcc, self.I2Cerr)) - -class MAVLink_radio_message(MAVLink_message): - ''' - Status generated by radio - ''' - def __init__(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RADIO, 'RADIO') - self._fieldnames = ['rssi', 'remrssi', 'txbuf', 'noise', 'remnoise', 'rxerrors', 'fixed'] - self.rssi = rssi - self.remrssi = remrssi - self.txbuf = txbuf - self.noise = noise - self.remnoise = remnoise - self.rxerrors = rxerrors - self.fixed = fixed - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 93, struct.pack('>BBBBBHH', self.rssi, self.remrssi, self.txbuf, self.noise, self.remnoise, self.rxerrors, self.fixed)) - -class MAVLink_heartbeat_message(MAVLink_message): - ''' - 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). - ''' - def __init__(self, type, autopilot, mavlink_version): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_HEARTBEAT, 'HEARTBEAT') - self._fieldnames = ['type', 'autopilot', 'mavlink_version'] - self.type = type - self.autopilot = autopilot - self.mavlink_version = mavlink_version - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 72, struct.pack('>BBB', self.type, self.autopilot, self.mavlink_version)) - -class MAVLink_boot_message(MAVLink_message): - ''' - The boot message indicates that a system is starting. The - onboard software version allows to keep track of onboard - soft/firmware revisions. - ''' - def __init__(self, version): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_BOOT, 'BOOT') - self._fieldnames = ['version'] - self.version = version - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 39, struct.pack('>I', self.version)) - -class MAVLink_system_time_message(MAVLink_message): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - ''' - def __init__(self, time_usec): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME, 'SYSTEM_TIME') - self._fieldnames = ['time_usec'] - self.time_usec = time_usec - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 190, struct.pack('>Q', self.time_usec)) - -class MAVLink_ping_message(MAVLink_message): - ''' - A ping message either requesting or responding to a ping. This - allows to measure the system latencies, including serial port, - radio modem and UDP connections. - ''' - def __init__(self, seq, target_system, target_component, time): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PING, 'PING') - self._fieldnames = ['seq', 'target_system', 'target_component', 'time'] - self.seq = seq - self.target_system = target_system - self.target_component = target_component - self.time = time - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 92, struct.pack('>IBBQ', self.seq, self.target_system, self.target_component, self.time)) - -class MAVLink_system_time_utc_message(MAVLink_message): - ''' - UTC date and time from GPS module - ''' - def __init__(self, utc_date, utc_time): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, 'SYSTEM_TIME_UTC') - self._fieldnames = ['utc_date', 'utc_time'] - self.utc_date = utc_date - self.utc_time = utc_time - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 191, struct.pack('>II', self.utc_date, self.utc_time)) - -class MAVLink_change_operator_control_message(MAVLink_message): - ''' - Request to control this MAV - ''' - def __init__(self, target_system, control_request, version, passkey): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, 'CHANGE_OPERATOR_CONTROL') - self._fieldnames = ['target_system', 'control_request', 'version', 'passkey'] - self.target_system = target_system - self.control_request = control_request - self.version = version - self.passkey = passkey - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 217, struct.pack('>BBB25s', self.target_system, self.control_request, self.version, self.passkey)) - -class MAVLink_change_operator_control_ack_message(MAVLink_message): - ''' - Accept / deny control of this MAV - ''' - def __init__(self, gcs_system_id, control_request, ack): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, 'CHANGE_OPERATOR_CONTROL_ACK') - self._fieldnames = ['gcs_system_id', 'control_request', 'ack'] - self.gcs_system_id = gcs_system_id - self.control_request = control_request - self.ack = ack - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 104, struct.pack('>BBB', self.gcs_system_id, self.control_request, self.ack)) - -class MAVLink_auth_key_message(MAVLink_message): - ''' - Emit an encrypted signature / key identifying this system. - PLEASE NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for true - safety. - ''' - def __init__(self, key): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_AUTH_KEY, 'AUTH_KEY') - self._fieldnames = ['key'] - self.key = key - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 119, struct.pack('>32s', self.key)) - -class MAVLink_action_ack_message(MAVLink_message): - ''' - This message acknowledges an action. IMPORTANT: The - acknowledgement can be also negative, e.g. the MAV rejects a - reset message because it is in-flight. The action ids are - defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h - ''' - def __init__(self, action, result): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ACTION_ACK, 'ACTION_ACK') - self._fieldnames = ['action', 'result'] - self.action = action - self.result = result - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 219, struct.pack('>BB', self.action, self.result)) - -class MAVLink_action_message(MAVLink_message): - ''' - An action message allows to execute a certain onboard action. - These include liftoff, land, storing parameters too EEPROM, - shutddown, etc. The action ids are defined in ENUM MAV_ACTION - in mavlink/include/mavlink_types.h - ''' - def __init__(self, target, target_component, action): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ACTION, 'ACTION') - self._fieldnames = ['target', 'target_component', 'action'] - self.target = target - self.target_component = target_component - self.action = action - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 60, struct.pack('>BBB', self.target, self.target_component, self.action)) - -class MAVLink_set_mode_message(MAVLink_message): - ''' - Set the system mode, as defined by enum MAV_MODE in - mavlink/include/mavlink_types.h. There is no target component - id as the mode is by definition for the overall aircraft, not - only for one component. - ''' - def __init__(self, target, mode): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_MODE, 'SET_MODE') - self._fieldnames = ['target', 'mode'] - self.target = target - self.mode = mode - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 186, struct.pack('>BB', self.target, self.mode)) - -class MAVLink_set_nav_mode_message(MAVLink_message): - ''' - Set the system navigation mode, as defined by enum - MAV_NAV_MODE in mavlink/include/mavlink_types.h. The - navigation mode applies to the whole aircraft and thus all - components. - ''' - def __init__(self, target, nav_mode): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_NAV_MODE, 'SET_NAV_MODE') - self._fieldnames = ['target', 'nav_mode'] - self.target = target - self.nav_mode = nav_mode - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 10, struct.pack('>BB', self.target, self.nav_mode)) - -class MAVLink_param_request_read_message(MAVLink_message): - ''' - Request to read the onboard parameter with the param_id string - id. Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any other - component (such as the GCS) without the need of previous - knowledge of possible parameter names. Thus the same GCS can - store different parameters for different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a full - documentation of QGroundControl and IMU code. - ''' - def __init__(self, target_system, target_component, param_id, param_index): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_READ, 'PARAM_REQUEST_READ') - self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] - self.target_system = target_system - self.target_component = target_component - self.param_id = param_id - self.param_index = param_index - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 89, struct.pack('>BB15sh', self.target_system, self.target_component, self.param_id, self.param_index)) - -class MAVLink_param_request_list_message(MAVLink_message): - ''' - Request all parameters of this component. After his request, - all parameters are emitted. - ''' - def __init__(self, target_system, target_component): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, 'PARAM_REQUEST_LIST') - self._fieldnames = ['target_system', 'target_component'] - self.target_system = target_system - self.target_component = target_component - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 159, struct.pack('>BB', self.target_system, self.target_component)) - -class MAVLink_param_value_message(MAVLink_message): - ''' - Emit the value of a onboard parameter. The inclusion of - param_count and param_index in the message allows the - recipient to keep track of received parameters and allows him - to re-request missing parameters after a loss or timeout. - ''' - def __init__(self, param_id, param_value, param_count, param_index): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_VALUE, 'PARAM_VALUE') - self._fieldnames = ['param_id', 'param_value', 'param_count', 'param_index'] - self.param_id = param_id - self.param_value = param_value - self.param_count = param_count - self.param_index = param_index - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 162, struct.pack('>15sfHH', self.param_id, self.param_value, self.param_count, self.param_index)) - -class MAVLink_param_set_message(MAVLink_message): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to - default on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents - to EEPROM. IMPORTANT: The receiving component should - acknowledge the new parameter value by sending a param_value - message to all communication partners. This will also ensure - that multiple GCS all have an up-to-date list of all - parameters. If the sending GCS did not receive a PARAM_VALUE - message within its timeout time, it should re-send the - PARAM_SET message. - ''' - def __init__(self, target_system, target_component, param_id, param_value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_SET, 'PARAM_SET') - self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_value'] - self.target_system = target_system - self.target_component = target_component - self.param_id = param_id - self.param_value = param_value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 121, struct.pack('>BB15sf', self.target_system, self.target_component, self.param_id, self.param_value)) - -class MAVLink_gps_raw_int_message(MAVLink_message): - ''' - The global position, as returned by the Global Positioning - System (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. Coordinate - frame is right-handed, Z-axis up (GPS frame) - ''' - def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW_INT, 'GPS_RAW_INT') - self._fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] - self.usec = usec - self.fix_type = fix_type - self.lat = lat - self.lon = lon - self.alt = alt - self.eph = eph - self.epv = epv - self.v = v - self.hdg = hdg - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 149, struct.pack('>QBiiiffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) - -class MAVLink_scaled_imu_message(MAVLink_message): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This - message should contain the scaled values to the described - units - ''' - def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_IMU, 'SCALED_IMU') - self._fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] - self.usec = usec - self.xacc = xacc - self.yacc = yacc - self.zacc = zacc - self.xgyro = xgyro - self.ygyro = ygyro - self.zgyro = zgyro - self.xmag = xmag - self.ymag = ymag - self.zmag = zmag - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 222, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) - -class MAVLink_gps_status_message(MAVLink_message): - ''' - The positioning status, as reported by GPS. This message is - intended to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION for the - global position estimate. This message can contain information - for up to 20 satellites. - ''' - def __init__(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_STATUS, 'GPS_STATUS') - self._fieldnames = ['satellites_visible', 'satellite_prn', 'satellite_used', 'satellite_elevation', 'satellite_azimuth', 'satellite_snr'] - self.satellites_visible = satellites_visible - self.satellite_prn = satellite_prn - self.satellite_used = satellite_used - self.satellite_elevation = satellite_elevation - self.satellite_azimuth = satellite_azimuth - self.satellite_snr = satellite_snr - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 110, struct.pack('>B20s20s20s20s20s', self.satellites_visible, self.satellite_prn, self.satellite_used, self.satellite_elevation, self.satellite_azimuth, self.satellite_snr)) - -class MAVLink_raw_imu_message(MAVLink_message): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This - message should always contain the true raw values without any - scaling to allow data capture and system debugging. - ''' - def __init__(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_IMU, 'RAW_IMU') - self._fieldnames = ['usec', 'xacc', 'yacc', 'zacc', 'xgyro', 'ygyro', 'zgyro', 'xmag', 'ymag', 'zmag'] - self.usec = usec - self.xacc = xacc - self.yacc = yacc - self.zacc = zacc - self.xgyro = xgyro - self.ygyro = ygyro - self.zgyro = zgyro - self.xmag = xmag - self.ymag = ymag - self.zmag = zmag - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 179, struct.pack('>Qhhhhhhhhh', self.usec, self.xacc, self.yacc, self.zacc, self.xgyro, self.ygyro, self.zgyro, self.xmag, self.ymag, self.zmag)) - -class MAVLink_raw_pressure_message(MAVLink_message): - ''' - The RAW pressure readings for the typical setup of one - absolute pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - ''' - def __init__(self, usec, press_abs, press_diff1, press_diff2, temperature): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RAW_PRESSURE, 'RAW_PRESSURE') - self._fieldnames = ['usec', 'press_abs', 'press_diff1', 'press_diff2', 'temperature'] - self.usec = usec - self.press_abs = press_abs - self.press_diff1 = press_diff1 - self.press_diff2 = press_diff2 - self.temperature = temperature - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 136, struct.pack('>Qhhhh', self.usec, self.press_abs, self.press_diff1, self.press_diff2, self.temperature)) - -class MAVLink_scaled_pressure_message(MAVLink_message): - ''' - The pressure readings for the typical setup of one absolute - and differential pressure sensor. The units are as specified - in each field. - ''' - def __init__(self, usec, press_abs, press_diff, temperature): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SCALED_PRESSURE, 'SCALED_PRESSURE') - self._fieldnames = ['usec', 'press_abs', 'press_diff', 'temperature'] - self.usec = usec - self.press_abs = press_abs - self.press_diff = press_diff - self.temperature = temperature - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 229, struct.pack('>Qffh', self.usec, self.press_abs, self.press_diff, self.temperature)) - -class MAVLink_attitude_message(MAVLink_message): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, - X-front, Y-right). - ''' - def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ATTITUDE, 'ATTITUDE') - self._fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed'] - self.usec = usec - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.rollspeed = rollspeed - self.pitchspeed = pitchspeed - self.yawspeed = yawspeed - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 66, struct.pack('>Qffffff', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed)) - -class MAVLink_local_position_message(MAVLink_message): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, Z-axis down - (aeronautical frame) - ''' - def __init__(self, usec, x, y, z, vx, vy, vz): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION, 'LOCAL_POSITION') - self._fieldnames = ['usec', 'x', 'y', 'z', 'vx', 'vy', 'vz'] - self.usec = usec - self.x = x - self.y = y - self.z = z - self.vx = vx - self.vy = vy - self.vz = vz - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 126, struct.pack('>Qffffff', self.usec, self.x, self.y, self.z, self.vx, self.vy, self.vz)) - -class MAVLink_global_position_message(MAVLink_message): - ''' - The filtered global position (e.g. fused GPS and - accelerometers). Coordinate frame is right-handed, Z-axis up - (GPS frame) - ''' - def __init__(self, usec, lat, lon, alt, vx, vy, vz): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION, 'GLOBAL_POSITION') - self._fieldnames = ['usec', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz'] - self.usec = usec - self.lat = lat - self.lon = lon - self.alt = alt - self.vx = vx - self.vy = vy - self.vz = vz - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 147, struct.pack('>Qffffff', self.usec, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) - -class MAVLink_gps_raw_message(MAVLink_message): - ''' - The global position, as returned by the Global Positioning - System (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. Coordinate - frame is right-handed, Z-axis up (GPS frame) - ''' - def __init__(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_RAW, 'GPS_RAW') - self._fieldnames = ['usec', 'fix_type', 'lat', 'lon', 'alt', 'eph', 'epv', 'v', 'hdg'] - self.usec = usec - self.fix_type = fix_type - self.lat = lat - self.lon = lon - self.alt = alt - self.eph = eph - self.epv = epv - self.v = v - self.hdg = hdg - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 185, struct.pack('>QBfffffff', self.usec, self.fix_type, self.lat, self.lon, self.alt, self.eph, self.epv, self.v, self.hdg)) - -class MAVLink_sys_status_message(MAVLink_message): - ''' - The general system state. If the system is following the - MAVLink standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is either - LOCKED (motors shut down and locked), MANUAL (system under RC - control), GUIDED (system with autonomous position control, - position setpoint controlled manually) or AUTO (system guided - by path/waypoint planner). The NAV_MODE defined the current - flight state: LIFTOFF (often an open-loop maneuver), LANDING, - WAYPOINTS or VECTOR. This represents the internal navigation - state machine. The system status shows wether the system is - currently active or not and if an emergency occured. During - the CRITICAL and EMERGENCY states the MAV is still considered - to be active, but should start emergency procedures - autonomously. After a failure occured it should first move - from active to critical to allow manual intervention and then - move to emergency after a certain timeout. - ''' - def __init__(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SYS_STATUS, 'SYS_STATUS') - self._fieldnames = ['mode', 'nav_mode', 'status', 'load', 'vbat', 'battery_remaining', 'packet_drop'] - self.mode = mode - self.nav_mode = nav_mode - self.status = status - self.load = load - self.vbat = vbat - self.battery_remaining = battery_remaining - self.packet_drop = packet_drop - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 112, struct.pack('>BBBHHHH', self.mode, self.nav_mode, self.status, self.load, self.vbat, self.battery_remaining, self.packet_drop)) - -class MAVLink_rc_channels_raw_message(MAVLink_message): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters might - violate this specification. - ''' - def __init__(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_RAW, 'RC_CHANNELS_RAW') - self._fieldnames = ['chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw', 'rssi'] - self.chan1_raw = chan1_raw - self.chan2_raw = chan2_raw - self.chan3_raw = chan3_raw - self.chan4_raw = chan4_raw - self.chan5_raw = chan5_raw - self.chan6_raw = chan6_raw - self.chan7_raw = chan7_raw - self.chan8_raw = chan8_raw - self.rssi = rssi - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 252, struct.pack('>HHHHHHHHB', self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw, self.rssi)) - -class MAVLink_rc_channels_scaled_message(MAVLink_message): - ''' - The scaled values of the RC channels received. (-100%) -10000, - (0%) 0, (100%) 10000 - ''' - def __init__(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, 'RC_CHANNELS_SCALED') - self._fieldnames = ['chan1_scaled', 'chan2_scaled', 'chan3_scaled', 'chan4_scaled', 'chan5_scaled', 'chan6_scaled', 'chan7_scaled', 'chan8_scaled', 'rssi'] - self.chan1_scaled = chan1_scaled - self.chan2_scaled = chan2_scaled - self.chan3_scaled = chan3_scaled - self.chan4_scaled = chan4_scaled - self.chan5_scaled = chan5_scaled - self.chan6_scaled = chan6_scaled - self.chan7_scaled = chan7_scaled - self.chan8_scaled = chan8_scaled - self.rssi = rssi - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 162, struct.pack('>hhhhhhhhB', self.chan1_scaled, self.chan2_scaled, self.chan3_scaled, self.chan4_scaled, self.chan5_scaled, self.chan6_scaled, self.chan7_scaled, self.chan8_scaled, self.rssi)) - -class MAVLink_servo_output_raw_message(MAVLink_message): - ''' - The RAW values of the servo outputs (for RC input from the - remote, use the RC_CHANNELS messages). The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - ''' - def __init__(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, 'SERVO_OUTPUT_RAW') - self._fieldnames = ['servo1_raw', 'servo2_raw', 'servo3_raw', 'servo4_raw', 'servo5_raw', 'servo6_raw', 'servo7_raw', 'servo8_raw'] - self.servo1_raw = servo1_raw - self.servo2_raw = servo2_raw - self.servo3_raw = servo3_raw - self.servo4_raw = servo4_raw - self.servo5_raw = servo5_raw - self.servo6_raw = servo6_raw - self.servo7_raw = servo7_raw - self.servo8_raw = servo8_raw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 215, struct.pack('>HHHHHHHH', self.servo1_raw, self.servo2_raw, self.servo3_raw, self.servo4_raw, self.servo5_raw, self.servo6_raw, self.servo7_raw, self.servo8_raw)) - -class MAVLink_waypoint_message(MAVLink_message): - ''' - Message encoding a waypoint. This message is emitted to - announce the presence of a waypoint and to set a waypoint - on the system. The waypoint can be either in x, y, z meters - (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is - Z-down, right handed, global frame is Z-up, right handed - ''' - def __init__(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT, 'WAYPOINT') - self._fieldnames = ['target_system', 'target_component', 'seq', 'frame', 'command', 'current', 'autocontinue', 'param1', 'param2', 'param3', 'param4', 'x', 'y', 'z'] - self.target_system = target_system - self.target_component = target_component - self.seq = seq - self.frame = frame - self.command = command - self.current = current - self.autocontinue = autocontinue - self.param1 = param1 - self.param2 = param2 - self.param3 = param3 - self.param4 = param4 - self.x = x - self.y = y - self.z = z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 128, struct.pack('>BBHBBBBfffffff', self.target_system, self.target_component, self.seq, self.frame, self.command, self.current, self.autocontinue, self.param1, self.param2, self.param3, self.param4, self.x, self.y, self.z)) - -class MAVLink_waypoint_request_message(MAVLink_message): - ''' - Request the information of the waypoint with the sequence - number seq. The response of the system to this message should - be a WAYPOINT message. - ''' - def __init__(self, target_system, target_component, seq): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_REQUEST, 'WAYPOINT_REQUEST') - self._fieldnames = ['target_system', 'target_component', 'seq'] - self.target_system = target_system - self.target_component = target_component - self.seq = seq - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 9, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) - -class MAVLink_waypoint_set_current_message(MAVLink_message): - ''' - Set the waypoint with sequence number seq as current waypoint. - This means that the MAV will continue to this waypoint on the - shortest path (not following the waypoints in-between). - ''' - def __init__(self, target_system, target_component, seq): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT, 'WAYPOINT_SET_CURRENT') - self._fieldnames = ['target_system', 'target_component', 'seq'] - self.target_system = target_system - self.target_component = target_component - self.seq = seq - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 106, struct.pack('>BBH', self.target_system, self.target_component, self.seq)) - -class MAVLink_waypoint_current_message(MAVLink_message): - ''' - Message that announces the sequence number of the current - active waypoint. The MAV will fly towards this waypoint. - ''' - def __init__(self, seq): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_CURRENT, 'WAYPOINT_CURRENT') - self._fieldnames = ['seq'] - self.seq = seq - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 101, struct.pack('>H', self.seq)) - -class MAVLink_waypoint_request_list_message(MAVLink_message): - ''' - Request the overall list of waypoints from the - system/component. - ''' - def __init__(self, target_system, target_component): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST, 'WAYPOINT_REQUEST_LIST') - self._fieldnames = ['target_system', 'target_component'] - self.target_system = target_system - self.target_component = target_component - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 213, struct.pack('>BB', self.target_system, self.target_component)) - -class MAVLink_waypoint_count_message(MAVLink_message): - ''' - This message is emitted as response to WAYPOINT_REQUEST_LIST - by the MAV. The GCS can then request the individual waypoints - based on the knowledge of the total number of waypoints. - ''' - def __init__(self, target_system, target_component, count): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_COUNT, 'WAYPOINT_COUNT') - self._fieldnames = ['target_system', 'target_component', 'count'] - self.target_system = target_system - self.target_component = target_component - self.count = count - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 4, struct.pack('>BBH', self.target_system, self.target_component, self.count)) - -class MAVLink_waypoint_clear_all_message(MAVLink_message): - ''' - Delete all waypoints at once. - ''' - def __init__(self, target_system, target_component): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL, 'WAYPOINT_CLEAR_ALL') - self._fieldnames = ['target_system', 'target_component'] - self.target_system = target_system - self.target_component = target_component - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 229, struct.pack('>BB', self.target_system, self.target_component)) - -class MAVLink_waypoint_reached_message(MAVLink_message): - ''' - A certain waypoint has been reached. The system will either - hold this position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next waypoint. - ''' - def __init__(self, seq): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_REACHED, 'WAYPOINT_REACHED') - self._fieldnames = ['seq'] - self.seq = seq - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 21, struct.pack('>H', self.seq)) - -class MAVLink_waypoint_ack_message(MAVLink_message): - ''' - Ack message during waypoint handling. The type field states if - this message is a positive ack (type=0) or if an error - happened (type=non-zero). - ''' - def __init__(self, target_system, target_component, type): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_WAYPOINT_ACK, 'WAYPOINT_ACK') - self._fieldnames = ['target_system', 'target_component', 'type'] - self.target_system = target_system - self.target_component = target_component - self.type = type - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 214, struct.pack('>BBB', self.target_system, self.target_component, self.type)) - -class MAVLink_gps_set_global_origin_message(MAVLink_message): - ''' - As local waypoints exist, the global waypoint reference allows - to transform between the local coordinate frame and the global - (GPS) coordinate frame. This can be necessary when e.g. in- - and outdoor settings are connected and the MAV should move - from in- to outdoor. - ''' - def __init__(self, target_system, target_component, latitude, longitude, altitude): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, 'GPS_SET_GLOBAL_ORIGIN') - self._fieldnames = ['target_system', 'target_component', 'latitude', 'longitude', 'altitude'] - self.target_system = target_system - self.target_component = target_component - self.latitude = latitude - self.longitude = longitude - self.altitude = altitude - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 215, struct.pack('>BBiii', self.target_system, self.target_component, self.latitude, self.longitude, self.altitude)) - -class MAVLink_gps_local_origin_set_message(MAVLink_message): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - ''' - def __init__(self, latitude, longitude, altitude): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET, 'GPS_LOCAL_ORIGIN_SET') - self._fieldnames = ['latitude', 'longitude', 'altitude'] - self.latitude = latitude - self.longitude = longitude - self.altitude = altitude - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 14, struct.pack('>iii', self.latitude, self.longitude, self.altitude)) - -class MAVLink_local_position_setpoint_set_message(MAVLink_message): - ''' - Set the setpoint for a local position controller. This is the - position in local coordinates the MAV should fly to. This - message is sent by the path/waypoint planner to the onboard - position controller. As some MAVs have a degree of freedom in - yaw (e.g. all helicopters/quadrotors), the desired yaw angle - is part of the message. - ''' - def __init__(self, target_system, target_component, x, y, z, yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET, 'LOCAL_POSITION_SETPOINT_SET') - self._fieldnames = ['target_system', 'target_component', 'x', 'y', 'z', 'yaw'] - self.target_system = target_system - self.target_component = target_component - self.x = x - self.y = y - self.z = z - self.yaw = yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 206, struct.pack('>BBffff', self.target_system, self.target_component, self.x, self.y, self.z, self.yaw)) - -class MAVLink_local_position_setpoint_message(MAVLink_message): - ''' - Transmit the current local setpoint of the controller to other - MAVs (collision avoidance) and to the GCS. - ''' - def __init__(self, x, y, z, yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, 'LOCAL_POSITION_SETPOINT') - self._fieldnames = ['x', 'y', 'z', 'yaw'] - self.x = x - self.y = y - self.z = z - self.yaw = yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 50, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) - -class MAVLink_control_status_message(MAVLink_message): - ''' - - ''' - def __init__(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_CONTROL_STATUS, 'CONTROL_STATUS') - self._fieldnames = ['position_fix', 'vision_fix', 'gps_fix', 'ahrs_health', 'control_att', 'control_pos_xy', 'control_pos_z', 'control_pos_yaw'] - self.position_fix = position_fix - self.vision_fix = vision_fix - self.gps_fix = gps_fix - self.ahrs_health = ahrs_health - self.control_att = control_att - self.control_pos_xy = control_pos_xy - self.control_pos_z = control_pos_z - self.control_pos_yaw = control_pos_yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 157, struct.pack('>BBBBBBBB', self.position_fix, self.vision_fix, self.gps_fix, self.ahrs_health, self.control_att, self.control_pos_xy, self.control_pos_z, self.control_pos_yaw)) - -class MAVLink_safety_set_allowed_area_message(MAVLink_message): - ''' - Set a safety zone (volume), which is defined by two corners of - a cube. This message can be used to tell the MAV which - setpoints/waypoints to accept and which to reject. Safety - areas are often enforced by national or competition - regulations. - ''' - def __init__(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, 'SAFETY_SET_ALLOWED_AREA') - self._fieldnames = ['target_system', 'target_component', 'frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] - self.target_system = target_system - self.target_component = target_component - self.frame = frame - self.p1x = p1x - self.p1y = p1y - self.p1z = p1z - self.p2x = p2x - self.p2y = p2y - self.p2z = p2z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 126, struct.pack('>BBBffffff', self.target_system, self.target_component, self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) - -class MAVLink_safety_allowed_area_message(MAVLink_message): - ''' - Read out the safety zone the MAV currently assumes. - ''' - def __init__(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, 'SAFETY_ALLOWED_AREA') - self._fieldnames = ['frame', 'p1x', 'p1y', 'p1z', 'p2x', 'p2y', 'p2z'] - self.frame = frame - self.p1x = p1x - self.p1y = p1y - self.p1z = p1z - self.p2x = p2x - self.p2y = p2y - self.p2z = p2z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 108, struct.pack('>Bffffff', self.frame, self.p1x, self.p1y, self.p1z, self.p2x, self.p2y, self.p2z)) - -class MAVLink_set_roll_pitch_yaw_thrust_message(MAVLink_message): - ''' - Set roll, pitch and yaw. - ''' - def __init__(self, target_system, target_component, roll, pitch, yaw, thrust): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, 'SET_ROLL_PITCH_YAW_THRUST') - self._fieldnames = ['target_system', 'target_component', 'roll', 'pitch', 'yaw', 'thrust'] - self.target_system = target_system - self.target_component = target_component - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.thrust = thrust - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 213, struct.pack('>BBffff', self.target_system, self.target_component, self.roll, self.pitch, self.yaw, self.thrust)) - -class MAVLink_set_roll_pitch_yaw_speed_thrust_message(MAVLink_message): - ''' - Set roll, pitch and yaw. - ''' - def __init__(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, 'SET_ROLL_PITCH_YAW_SPEED_THRUST') - self._fieldnames = ['target_system', 'target_component', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] - self.target_system = target_system - self.target_component = target_component - self.roll_speed = roll_speed - self.pitch_speed = pitch_speed - self.yaw_speed = yaw_speed - self.thrust = thrust - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 95, struct.pack('>BBffff', self.target_system, self.target_component, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) - -class MAVLink_roll_pitch_yaw_thrust_setpoint_message(MAVLink_message): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - ''' - def __init__(self, time_us, roll, pitch, yaw, thrust): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, 'ROLL_PITCH_YAW_THRUST_SETPOINT') - self._fieldnames = ['time_us', 'roll', 'pitch', 'yaw', 'thrust'] - self.time_us = time_us - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.thrust = thrust - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 5, struct.pack('>Qffff', self.time_us, self.roll, self.pitch, self.yaw, self.thrust)) - -class MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(MAVLink_message): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active - on the system. - ''' - def __init__(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, 'ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT') - self._fieldnames = ['time_us', 'roll_speed', 'pitch_speed', 'yaw_speed', 'thrust'] - self.time_us = time_us - self.roll_speed = roll_speed - self.pitch_speed = pitch_speed - self.yaw_speed = yaw_speed - self.thrust = thrust - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 127, struct.pack('>Qffff', self.time_us, self.roll_speed, self.pitch_speed, self.yaw_speed, self.thrust)) - -class MAVLink_nav_controller_output_message(MAVLink_message): - ''' - Outputs of the APM navigation controller. The primary use of - this message is to check the response and signs of the - controller before actual flight and to assist with tuning - controller parameters - ''' - def __init__(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, 'NAV_CONTROLLER_OUTPUT') - self._fieldnames = ['nav_roll', 'nav_pitch', 'nav_bearing', 'target_bearing', 'wp_dist', 'alt_error', 'aspd_error', 'xtrack_error'] - self.nav_roll = nav_roll - self.nav_pitch = nav_pitch - self.nav_bearing = nav_bearing - self.target_bearing = target_bearing - self.wp_dist = wp_dist - self.alt_error = alt_error - self.aspd_error = aspd_error - self.xtrack_error = xtrack_error - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 57, struct.pack('>ffhhHfff', self.nav_roll, self.nav_pitch, self.nav_bearing, self.target_bearing, self.wp_dist, self.alt_error, self.aspd_error, self.xtrack_error)) - -class MAVLink_position_target_message(MAVLink_message): - ''' - The goal position of the system. This position is the input to - any navigation or path planning algorithm and does NOT - represent the current controller setpoint. - ''' - def __init__(self, x, y, z, yaw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_POSITION_TARGET, 'POSITION_TARGET') - self._fieldnames = ['x', 'y', 'z', 'yaw'] - self.x = x - self.y = y - self.z = z - self.yaw = yaw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 126, struct.pack('>ffff', self.x, self.y, self.z, self.yaw)) - -class MAVLink_state_correction_message(MAVLink_message): - ''' - Corrects the systems state by adding an error correction term - to the position and velocity, and by rotating the attitude by - a correction angle. - ''' - def __init__(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_STATE_CORRECTION, 'STATE_CORRECTION') - self._fieldnames = ['xErr', 'yErr', 'zErr', 'rollErr', 'pitchErr', 'yawErr', 'vxErr', 'vyErr', 'vzErr'] - self.xErr = xErr - self.yErr = yErr - self.zErr = zErr - self.rollErr = rollErr - self.pitchErr = pitchErr - self.yawErr = yawErr - self.vxErr = vxErr - self.vyErr = vyErr - self.vzErr = vzErr - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 130, struct.pack('>fffffffff', self.xErr, self.yErr, self.zErr, self.rollErr, self.pitchErr, self.yawErr, self.vxErr, self.vyErr, self.vzErr)) - -class MAVLink_set_altitude_message(MAVLink_message): - ''' - - ''' - def __init__(self, target, mode): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_SET_ALTITUDE, 'SET_ALTITUDE') - self._fieldnames = ['target', 'mode'] - self.target = target - self.mode = mode - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 119, struct.pack('>BI', self.target, self.mode)) - -class MAVLink_request_data_stream_message(MAVLink_message): - ''' - - ''' - def __init__(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, 'REQUEST_DATA_STREAM') - self._fieldnames = ['target_system', 'target_component', 'req_stream_id', 'req_message_rate', 'start_stop'] - self.target_system = target_system - self.target_component = target_component - self.req_stream_id = req_stream_id - self.req_message_rate = req_message_rate - self.start_stop = start_stop - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 193, struct.pack('>BBBHB', self.target_system, self.target_component, self.req_stream_id, self.req_message_rate, self.start_stop)) - -class MAVLink_hil_state_message(MAVLink_message): - ''' - This packet is useful for high throughput - applications such as hardware in the loop simulations. - ''' - def __init__(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_STATE, 'HIL_STATE') - self._fieldnames = ['usec', 'roll', 'pitch', 'yaw', 'rollspeed', 'pitchspeed', 'yawspeed', 'lat', 'lon', 'alt', 'vx', 'vy', 'vz', 'xacc', 'yacc', 'zacc'] - self.usec = usec - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.rollspeed = rollspeed - self.pitchspeed = pitchspeed - self.yawspeed = yawspeed - self.lat = lat - self.lon = lon - self.alt = alt - self.vx = vx - self.vy = vy - self.vz = vz - self.xacc = xacc - self.yacc = yacc - self.zacc = zacc - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 191, struct.pack('>Qffffffiiihhhhhh', self.usec, self.roll, self.pitch, self.yaw, self.rollspeed, self.pitchspeed, self.yawspeed, self.lat, self.lon, self.alt, self.vx, self.vy, self.vz, self.xacc, self.yacc, self.zacc)) - -class MAVLink_hil_controls_message(MAVLink_message): - ''' - Hardware in the loop control outputs - ''' - def __init__(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_HIL_CONTROLS, 'HIL_CONTROLS') - self._fieldnames = ['time_us', 'roll_ailerons', 'pitch_elevator', 'yaw_rudder', 'throttle', 'mode', 'nav_mode'] - self.time_us = time_us - self.roll_ailerons = roll_ailerons - self.pitch_elevator = pitch_elevator - self.yaw_rudder = yaw_rudder - self.throttle = throttle - self.mode = mode - self.nav_mode = nav_mode - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 236, struct.pack('>QffffBB', self.time_us, self.roll_ailerons, self.pitch_elevator, self.yaw_rudder, self.throttle, self.mode, self.nav_mode)) - -class MAVLink_manual_control_message(MAVLink_message): - ''' - - ''' - def __init__(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_MANUAL_CONTROL, 'MANUAL_CONTROL') - self._fieldnames = ['target', 'roll', 'pitch', 'yaw', 'thrust', 'roll_manual', 'pitch_manual', 'yaw_manual', 'thrust_manual'] - self.target = target - self.roll = roll - self.pitch = pitch - self.yaw = yaw - self.thrust = thrust - self.roll_manual = roll_manual - self.pitch_manual = pitch_manual - self.yaw_manual = yaw_manual - self.thrust_manual = thrust_manual - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 158, struct.pack('>BffffBBBB', self.target, self.roll, self.pitch, self.yaw, self.thrust, self.roll_manual, self.pitch_manual, self.yaw_manual, self.thrust_manual)) - -class MAVLink_rc_channels_override_message(MAVLink_message): - ''' - The RAW values of the RC channels sent to the MAV to override - info received from the RC radio. A value of -1 means no change - to that channel. A value of 0 means control of that channel - should be released back to the RC radio. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters might - violate this specification. - ''' - def __init__(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, 'RC_CHANNELS_OVERRIDE') - self._fieldnames = ['target_system', 'target_component', 'chan1_raw', 'chan2_raw', 'chan3_raw', 'chan4_raw', 'chan5_raw', 'chan6_raw', 'chan7_raw', 'chan8_raw'] - self.target_system = target_system - self.target_component = target_component - self.chan1_raw = chan1_raw - self.chan2_raw = chan2_raw - self.chan3_raw = chan3_raw - self.chan4_raw = chan4_raw - self.chan5_raw = chan5_raw - self.chan6_raw = chan6_raw - self.chan7_raw = chan7_raw - self.chan8_raw = chan8_raw - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 143, struct.pack('>BBHHHHHHHH', self.target_system, self.target_component, self.chan1_raw, self.chan2_raw, self.chan3_raw, self.chan4_raw, self.chan5_raw, self.chan6_raw, self.chan7_raw, self.chan8_raw)) - -class MAVLink_global_position_int_message(MAVLink_message): - ''' - The filtered global position (e.g. fused GPS and - accelerometers). The position is in GPS-frame (right-handed, - Z-up) - ''' - def __init__(self, lat, lon, alt, vx, vy, vz): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, 'GLOBAL_POSITION_INT') - self._fieldnames = ['lat', 'lon', 'alt', 'vx', 'vy', 'vz'] - self.lat = lat - self.lon = lon - self.alt = alt - self.vx = vx - self.vy = vy - self.vz = vz - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 104, struct.pack('>iiihhh', self.lat, self.lon, self.alt, self.vx, self.vy, self.vz)) - -class MAVLink_vfr_hud_message(MAVLink_message): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - ''' - def __init__(self, airspeed, groundspeed, heading, throttle, alt, climb): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_VFR_HUD, 'VFR_HUD') - self._fieldnames = ['airspeed', 'groundspeed', 'heading', 'throttle', 'alt', 'climb'] - self.airspeed = airspeed - self.groundspeed = groundspeed - self.heading = heading - self.throttle = throttle - self.alt = alt - self.climb = climb - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 123, struct.pack('>ffhHff', self.airspeed, self.groundspeed, self.heading, self.throttle, self.alt, self.climb)) - -class MAVLink_command_message(MAVLink_message): - ''' - Send a command with up to four parameters to the MAV - ''' - def __init__(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_COMMAND, 'COMMAND') - self._fieldnames = ['target_system', 'target_component', 'command', 'confirmation', 'param1', 'param2', 'param3', 'param4'] - self.target_system = target_system - self.target_component = target_component - self.command = command - self.confirmation = confirmation - self.param1 = param1 - self.param2 = param2 - self.param3 = param3 - self.param4 = param4 - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 131, struct.pack('>BBBBffff', self.target_system, self.target_component, self.command, self.confirmation, self.param1, self.param2, self.param3, self.param4)) - -class MAVLink_command_ack_message(MAVLink_message): - ''' - Report status of a command. Includes feedback wether the - command was executed - ''' - def __init__(self, command, result): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_COMMAND_ACK, 'COMMAND_ACK') - self._fieldnames = ['command', 'result'] - self.command = command - self.result = result - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 8, struct.pack('>ff', self.command, self.result)) - -class MAVLink_optical_flow_message(MAVLink_message): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - ''' - def __init__(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_OPTICAL_FLOW, 'OPTICAL_FLOW') - self._fieldnames = ['time', 'sensor_id', 'flow_x', 'flow_y', 'quality', 'ground_distance'] - self.time = time - self.sensor_id = sensor_id - self.flow_x = flow_x - self.flow_y = flow_y - self.quality = quality - self.ground_distance = ground_distance - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 174, struct.pack('>QBhhBf', self.time, self.sensor_id, self.flow_x, self.flow_y, self.quality, self.ground_distance)) - -class MAVLink_object_detection_event_message(MAVLink_message): - ''' - Object has been detected - ''' - def __init__(self, time, object_id, type, name, quality, bearing, distance): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT, 'OBJECT_DETECTION_EVENT') - self._fieldnames = ['time', 'object_id', 'type', 'name', 'quality', 'bearing', 'distance'] - self.time = time - self.object_id = object_id - self.type = type - self.name = name - self.quality = quality - self.bearing = bearing - self.distance = distance - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 155, struct.pack('>IHB20sBff', self.time, self.object_id, self.type, self.name, self.quality, self.bearing, self.distance)) - -class MAVLink_debug_vect_message(MAVLink_message): - ''' - - ''' - def __init__(self, name, usec, x, y, z): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG_VECT, 'DEBUG_VECT') - self._fieldnames = ['name', 'usec', 'x', 'y', 'z'] - self.name = name - self.usec = usec - self.x = x - self.y = y - self.z = z - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 178, struct.pack('>10sQfff', self.name, self.usec, self.x, self.y, self.z)) - -class MAVLink_named_value_float_message(MAVLink_message): - ''' - Send a key-value pair as float. The use of this message is - discouraged for normal packets, but a quite efficient way for - testing new messages and getting experimental debug output. - ''' - def __init__(self, name, value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, 'NAMED_VALUE_FLOAT') - self._fieldnames = ['name', 'value'] - self.name = name - self.value = value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 224, struct.pack('>10sf', self.name, self.value)) - -class MAVLink_named_value_int_message(MAVLink_message): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient way for - testing new messages and getting experimental debug output. - ''' - def __init__(self, name, value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_NAMED_VALUE_INT, 'NAMED_VALUE_INT') - self._fieldnames = ['name', 'value'] - self.name = name - self.value = value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 60, struct.pack('>10si', self.name, self.value)) - -class MAVLink_statustext_message(MAVLink_message): - ''' - Status text message. These messages are printed in yellow in - the COMM console of QGroundControl. WARNING: They consume - quite some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages are - buffered on the MCU and sent only at a limited rate (e.g. 10 - Hz). - ''' - def __init__(self, severity, text): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_STATUSTEXT, 'STATUSTEXT') - self._fieldnames = ['severity', 'text'] - self.severity = severity - self.text = text - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 106, struct.pack('>B50s', self.severity, self.text)) - -class MAVLink_debug_message(MAVLink_message): - ''' - Send a debug value. The index is used to discriminate between - values. These values show up in the plot of QGroundControl as - DEBUG N. - ''' - def __init__(self, ind, value): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_DEBUG, 'DEBUG') - self._fieldnames = ['ind', 'value'] - self.ind = ind - self.value = value - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 7, struct.pack('>Bf', self.ind, self.value)) - - -mavlink_map = { - MAVLINK_MSG_ID_SENSOR_OFFSETS : ( '>hhhfiiffffff', MAVLink_sensor_offsets_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11], 143 ), - MAVLINK_MSG_ID_SET_MAG_OFFSETS : ( '>BBhhh', MAVLink_set_mag_offsets_message, [0, 1, 2, 3, 4], 29 ), - MAVLINK_MSG_ID_MEMINFO : ( '>HH', MAVLink_meminfo_message, [0, 1], 208 ), - MAVLINK_MSG_ID_AP_ADC : ( '>HHHHHH', MAVLink_ap_adc_message, [0, 1, 2, 3, 4, 5], 188 ), - MAVLINK_MSG_ID_DIGICAM_CONFIGURE : ( '>BBBHBBBBBBf', MAVLink_digicam_configure_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10], 118 ), - MAVLINK_MSG_ID_DIGICAM_CONTROL : ( '>BBBBbBBBBf', MAVLink_digicam_control_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 242 ), - MAVLINK_MSG_ID_MOUNT_CONFIGURE : ( '>BBBBBB', MAVLink_mount_configure_message, [0, 1, 2, 3, 4, 5], 19 ), - MAVLINK_MSG_ID_MOUNT_CONTROL : ( '>BBiiiB', MAVLink_mount_control_message, [0, 1, 2, 3, 4, 5], 97 ), - MAVLINK_MSG_ID_MOUNT_STATUS : ( '>BBiii', MAVLink_mount_status_message, [0, 1, 2, 3, 4], 233 ), - MAVLINK_MSG_ID_FENCE_POINT : ( '>BBBBff', MAVLink_fence_point_message, [0, 1, 2, 3, 4, 5], 18 ), - MAVLINK_MSG_ID_FENCE_FETCH_POINT : ( '>BBB', MAVLink_fence_fetch_point_message, [0, 1, 2], 68 ), - MAVLINK_MSG_ID_FENCE_STATUS : ( '>BHBI', MAVLink_fence_status_message, [0, 1, 2, 3], 136 ), - MAVLINK_MSG_ID_AHRS : ( '>fffffff', MAVLink_ahrs_message, [0, 1, 2, 3, 4, 5, 6], 127 ), - MAVLINK_MSG_ID_SIMSTATE : ( '>fffffffff', MAVLink_simstate_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 42 ), - MAVLINK_MSG_ID_HWSTATUS : ( '>HB', MAVLink_hwstatus_message, [0, 1], 21 ), - MAVLINK_MSG_ID_RADIO : ( '>BBBBBHH', MAVLink_radio_message, [0, 1, 2, 3, 4, 5, 6], 93 ), - MAVLINK_MSG_ID_HEARTBEAT : ( '>BBB', MAVLink_heartbeat_message, [0, 1, 2], 72 ), - MAVLINK_MSG_ID_BOOT : ( '>I', MAVLink_boot_message, [0], 39 ), - MAVLINK_MSG_ID_SYSTEM_TIME : ( '>Q', MAVLink_system_time_message, [0], 190 ), - MAVLINK_MSG_ID_PING : ( '>IBBQ', MAVLink_ping_message, [0, 1, 2, 3], 92 ), - MAVLINK_MSG_ID_SYSTEM_TIME_UTC : ( '>II', MAVLink_system_time_utc_message, [0, 1], 191 ), - MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL : ( '>BBB25s', MAVLink_change_operator_control_message, [0, 1, 2, 3], 217 ), - MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK : ( '>BBB', MAVLink_change_operator_control_ack_message, [0, 1, 2], 104 ), - MAVLINK_MSG_ID_AUTH_KEY : ( '>32s', MAVLink_auth_key_message, [0], 119 ), - MAVLINK_MSG_ID_ACTION_ACK : ( '>BB', MAVLink_action_ack_message, [0, 1], 219 ), - MAVLINK_MSG_ID_ACTION : ( '>BBB', MAVLink_action_message, [0, 1, 2], 60 ), - MAVLINK_MSG_ID_SET_MODE : ( '>BB', MAVLink_set_mode_message, [0, 1], 186 ), - MAVLINK_MSG_ID_SET_NAV_MODE : ( '>BB', MAVLink_set_nav_mode_message, [0, 1], 10 ), - MAVLINK_MSG_ID_PARAM_REQUEST_READ : ( '>BB15sh', MAVLink_param_request_read_message, [0, 1, 2, 3], 89 ), - MAVLINK_MSG_ID_PARAM_REQUEST_LIST : ( '>BB', MAVLink_param_request_list_message, [0, 1], 159 ), - MAVLINK_MSG_ID_PARAM_VALUE : ( '>15sfHH', MAVLink_param_value_message, [0, 1, 2, 3], 162 ), - MAVLINK_MSG_ID_PARAM_SET : ( '>BB15sf', MAVLink_param_set_message, [0, 1, 2, 3], 121 ), - MAVLINK_MSG_ID_GPS_RAW_INT : ( '>QBiiiffff', MAVLink_gps_raw_int_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 149 ), - MAVLINK_MSG_ID_SCALED_IMU : ( '>Qhhhhhhhhh', MAVLink_scaled_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 222 ), - MAVLINK_MSG_ID_GPS_STATUS : ( '>B20s20s20s20s20s', MAVLink_gps_status_message, [0, 1, 2, 3, 4, 5], 110 ), - MAVLINK_MSG_ID_RAW_IMU : ( '>Qhhhhhhhhh', MAVLink_raw_imu_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 179 ), - MAVLINK_MSG_ID_RAW_PRESSURE : ( '>Qhhhh', MAVLink_raw_pressure_message, [0, 1, 2, 3, 4], 136 ), - MAVLINK_MSG_ID_SCALED_PRESSURE : ( '>Qffh', MAVLink_scaled_pressure_message, [0, 1, 2, 3], 229 ), - MAVLINK_MSG_ID_ATTITUDE : ( '>Qffffff', MAVLink_attitude_message, [0, 1, 2, 3, 4, 5, 6], 66 ), - MAVLINK_MSG_ID_LOCAL_POSITION : ( '>Qffffff', MAVLink_local_position_message, [0, 1, 2, 3, 4, 5, 6], 126 ), - MAVLINK_MSG_ID_GLOBAL_POSITION : ( '>Qffffff', MAVLink_global_position_message, [0, 1, 2, 3, 4, 5, 6], 147 ), - MAVLINK_MSG_ID_GPS_RAW : ( '>QBfffffff', MAVLink_gps_raw_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 185 ), - MAVLINK_MSG_ID_SYS_STATUS : ( '>BBBHHHH', MAVLink_sys_status_message, [0, 1, 2, 3, 4, 5, 6], 112 ), - MAVLINK_MSG_ID_RC_CHANNELS_RAW : ( '>HHHHHHHHB', MAVLink_rc_channels_raw_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 252 ), - MAVLINK_MSG_ID_RC_CHANNELS_SCALED : ( '>hhhhhhhhB', MAVLink_rc_channels_scaled_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 162 ), - MAVLINK_MSG_ID_SERVO_OUTPUT_RAW : ( '>HHHHHHHH', MAVLink_servo_output_raw_message, [0, 1, 2, 3, 4, 5, 6, 7], 215 ), - MAVLINK_MSG_ID_WAYPOINT : ( '>BBHBBBBfffffff', MAVLink_waypoint_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13], 128 ), - MAVLINK_MSG_ID_WAYPOINT_REQUEST : ( '>BBH', MAVLink_waypoint_request_message, [0, 1, 2], 9 ), - MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT : ( '>BBH', MAVLink_waypoint_set_current_message, [0, 1, 2], 106 ), - MAVLINK_MSG_ID_WAYPOINT_CURRENT : ( '>H', MAVLink_waypoint_current_message, [0], 101 ), - MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST : ( '>BB', MAVLink_waypoint_request_list_message, [0, 1], 213 ), - MAVLINK_MSG_ID_WAYPOINT_COUNT : ( '>BBH', MAVLink_waypoint_count_message, [0, 1, 2], 4 ), - MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL : ( '>BB', MAVLink_waypoint_clear_all_message, [0, 1], 229 ), - MAVLINK_MSG_ID_WAYPOINT_REACHED : ( '>H', MAVLink_waypoint_reached_message, [0], 21 ), - MAVLINK_MSG_ID_WAYPOINT_ACK : ( '>BBB', MAVLink_waypoint_ack_message, [0, 1, 2], 214 ), - MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN : ( '>BBiii', MAVLink_gps_set_global_origin_message, [0, 1, 2, 3, 4], 215 ), - MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET : ( '>iii', MAVLink_gps_local_origin_set_message, [0, 1, 2], 14 ), - MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET : ( '>BBffff', MAVLink_local_position_setpoint_set_message, [0, 1, 2, 3, 4, 5], 206 ), - MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT : ( '>ffff', MAVLink_local_position_setpoint_message, [0, 1, 2, 3], 50 ), - MAVLINK_MSG_ID_CONTROL_STATUS : ( '>BBBBBBBB', MAVLink_control_status_message, [0, 1, 2, 3, 4, 5, 6, 7], 157 ), - MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA : ( '>BBBffffff', MAVLink_safety_set_allowed_area_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 126 ), - MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA : ( '>Bffffff', MAVLink_safety_allowed_area_message, [0, 1, 2, 3, 4, 5, 6], 108 ), - MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST : ( '>BBffff', MAVLink_set_roll_pitch_yaw_thrust_message, [0, 1, 2, 3, 4, 5], 213 ), - MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST : ( '>BBffff', MAVLink_set_roll_pitch_yaw_speed_thrust_message, [0, 1, 2, 3, 4, 5], 95 ), - MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT : ( '>Qffff', MAVLink_roll_pitch_yaw_thrust_setpoint_message, [0, 1, 2, 3, 4], 5 ), - MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT : ( '>Qffff', MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message, [0, 1, 2, 3, 4], 127 ), - MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT : ( '>ffhhHfff', MAVLink_nav_controller_output_message, [0, 1, 2, 3, 4, 5, 6, 7], 57 ), - MAVLINK_MSG_ID_POSITION_TARGET : ( '>ffff', MAVLink_position_target_message, [0, 1, 2, 3], 126 ), - MAVLINK_MSG_ID_STATE_CORRECTION : ( '>fffffffff', MAVLink_state_correction_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 130 ), - MAVLINK_MSG_ID_SET_ALTITUDE : ( '>BI', MAVLink_set_altitude_message, [0, 1], 119 ), - MAVLINK_MSG_ID_REQUEST_DATA_STREAM : ( '>BBBHB', MAVLink_request_data_stream_message, [0, 1, 2, 3, 4], 193 ), - MAVLINK_MSG_ID_HIL_STATE : ( '>Qffffffiiihhhhhh', MAVLink_hil_state_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15], 191 ), - MAVLINK_MSG_ID_HIL_CONTROLS : ( '>QffffBB', MAVLink_hil_controls_message, [0, 1, 2, 3, 4, 5, 6], 236 ), - MAVLINK_MSG_ID_MANUAL_CONTROL : ( '>BffffBBBB', MAVLink_manual_control_message, [0, 1, 2, 3, 4, 5, 6, 7, 8], 158 ), - MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE : ( '>BBHHHHHHHH', MAVLink_rc_channels_override_message, [0, 1, 2, 3, 4, 5, 6, 7, 8, 9], 143 ), - MAVLINK_MSG_ID_GLOBAL_POSITION_INT : ( '>iiihhh', MAVLink_global_position_int_message, [0, 1, 2, 3, 4, 5], 104 ), - MAVLINK_MSG_ID_VFR_HUD : ( '>ffhHff', MAVLink_vfr_hud_message, [0, 1, 2, 3, 4, 5], 123 ), - MAVLINK_MSG_ID_COMMAND : ( '>BBBBffff', MAVLink_command_message, [0, 1, 2, 3, 4, 5, 6, 7], 131 ), - MAVLINK_MSG_ID_COMMAND_ACK : ( '>ff', MAVLink_command_ack_message, [0, 1], 8 ), - MAVLINK_MSG_ID_OPTICAL_FLOW : ( '>QBhhBf', MAVLink_optical_flow_message, [0, 1, 2, 3, 4, 5], 174 ), - MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT : ( '>IHB20sBff', MAVLink_object_detection_event_message, [0, 1, 2, 3, 4, 5, 6], 155 ), - MAVLINK_MSG_ID_DEBUG_VECT : ( '>10sQfff', MAVLink_debug_vect_message, [0, 1, 2, 3, 4], 178 ), - MAVLINK_MSG_ID_NAMED_VALUE_FLOAT : ( '>10sf', MAVLink_named_value_float_message, [0, 1], 224 ), - MAVLINK_MSG_ID_NAMED_VALUE_INT : ( '>10si', MAVLink_named_value_int_message, [0, 1], 60 ), - MAVLINK_MSG_ID_STATUSTEXT : ( '>B50s', MAVLink_statustext_message, [0, 1], 106 ), - MAVLINK_MSG_ID_DEBUG : ( '>Bf', MAVLink_debug_message, [0, 1], 7 ), -} - -class MAVError(Exception): - '''MAVLink error class''' - def __init__(self, msg): - Exception.__init__(self, msg) - self.message = msg - -class MAVString(str): - '''NUL terminated string''' - def __init__(self, s): - str.__init__(self) - def __str__(self): - i = self.find(chr(0)) - if i == -1: - return self[:] - return self[0:i] - -class MAVLink_bad_data(MAVLink_message): - ''' - a piece of bad data in a mavlink stream - ''' - def __init__(self, data, reason): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_BAD_DATA, 'BAD_DATA') - self._fieldnames = ['data', 'reason'] - self.data = data - self.reason = reason - self._msgbuf = data - -class MAVLink(object): - '''MAVLink protocol handling class''' - def __init__(self, file, srcSystem=0, srcComponent=0): - self.seq = 0 - self.file = file - self.srcSystem = srcSystem - self.srcComponent = srcComponent - self.callback = None - self.callback_args = None - self.callback_kwargs = None - self.buf = array.array('B') - self.expected_length = 6 - self.have_prefix_error = False - self.robust_parsing = False - self.protocol_marker = 85 - self.little_endian = False - self.crc_extra = False - self.sort_fields = False - self.total_packets_sent = 0 - self.total_bytes_sent = 0 - self.total_packets_received = 0 - self.total_bytes_received = 0 - self.total_receive_errors = 0 - self.startup_time = time.time() - - def set_callback(self, callback, *args, **kwargs): - self.callback = callback - self.callback_args = args - self.callback_kwargs = kwargs - - def send(self, mavmsg): - '''send a MAVLink message''' - buf = mavmsg.pack(self) - self.file.write(buf) - self.seq = (self.seq + 1) % 255 - self.total_packets_sent += 1 - self.total_bytes_sent += len(buf) - - def bytes_needed(self): - '''return number of bytes needed for next parsing stage''' - ret = self.expected_length - len(self.buf) - if ret <= 0: - return 1 - return ret - - def parse_char(self, c): - '''input some data bytes, possibly returning a new message''' - if isinstance(c, str): - self.buf.fromstring(c) - else: - self.buf.extend(c) - self.total_bytes_received += len(c) - if len(self.buf) >= 1 and self.buf[0] != 85: - magic = self.buf[0] - self.buf = self.buf[1:] - if self.robust_parsing: - m = MAVLink_bad_data(chr(magic), "Bad prefix") - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - self.expected_length = 6 - self.total_receive_errors += 1 - return m - if self.have_prefix_error: - return None - self.have_prefix_error = True - self.total_receive_errors += 1 - raise MAVError("invalid MAVLink prefix '%s'" % magic) - self.have_prefix_error = False - if len(self.buf) >= 2: - (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) - self.expected_length += 8 - if self.expected_length >= 8 and len(self.buf) >= self.expected_length: - mbuf = self.buf[0:self.expected_length] - self.buf = self.buf[self.expected_length:] - self.expected_length = 6 - if self.robust_parsing: - try: - m = self.decode(mbuf) - self.total_packets_received += 1 - except MAVError as reason: - m = MAVLink_bad_data(mbuf, reason.message) - self.total_receive_errors += 1 - else: - m = self.decode(mbuf) - self.total_packets_received += 1 - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - return m - return None - - def parse_buffer(self, s): - '''input some data bytes, possibly returning a list of new messages''' - m = self.parse_char(s) - if m is None: - return None - ret = [m] - while True: - m = self.parse_char("") - if m is None: - return ret - ret.append(m) - return ret - - def decode(self, msgbuf): - '''decode a buffer as a MAVLink message''' - # decode the header - try: - magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) - except struct.error as emsg: - raise MAVError('Unable to unpack MAVLink header: %s' % emsg) - if ord(magic) != 85: - raise MAVError("invalid MAVLink prefix '%s'" % magic) - if mlen != len(msgbuf)-8: - raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) - - if not msgId in mavlink_map: - raise MAVError('unknown MAVLink message ID %u' % msgId) - - # decode the payload - (fmt, type, order_map, crc_extra) = mavlink_map[msgId] - - # decode the checksum - try: - crc, = struct.unpack(' MAV. - Also used to return a point from MAV -> GCS - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - count : total number of points (for sanity checking) (uint8_t) - lat : Latitude of point (float) - lng : Longitude of point (float) - - ''' - msg = MAVLink_fence_point_message(target_system, target_component, idx, count, lat, lng) - msg.pack(self) - return msg - - def fence_point_send(self, target_system, target_component, idx, count, lat, lng): - ''' - A fence point. Used to set a point when from GCS -> MAV. - Also used to return a point from MAV -> GCS - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - count : total number of points (for sanity checking) (uint8_t) - lat : Latitude of point (float) - lng : Longitude of point (float) - - ''' - return self.send(self.fence_point_encode(target_system, target_component, idx, count, lat, lng)) - - def fence_fetch_point_encode(self, target_system, target_component, idx): - ''' - Request a current fence point from MAV - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - - ''' - msg = MAVLink_fence_fetch_point_message(target_system, target_component, idx) - msg.pack(self) - return msg - - def fence_fetch_point_send(self, target_system, target_component, idx): - ''' - Request a current fence point from MAV - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - - ''' - return self.send(self.fence_fetch_point_encode(target_system, target_component, idx)) - - def fence_status_encode(self, breach_status, breach_count, breach_type, breach_time): - ''' - Status of geo-fencing. Sent in extended status stream when - fencing enabled - - breach_status : 0 if currently inside fence, 1 if outside (uint8_t) - breach_count : number of fence breaches (uint16_t) - breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) - breach_time : time of last breach in milliseconds since boot (uint32_t) - - ''' - msg = MAVLink_fence_status_message(breach_status, breach_count, breach_type, breach_time) - msg.pack(self) - return msg - - def fence_status_send(self, breach_status, breach_count, breach_type, breach_time): - ''' - Status of geo-fencing. Sent in extended status stream when - fencing enabled - - breach_status : 0 if currently inside fence, 1 if outside (uint8_t) - breach_count : number of fence breaches (uint16_t) - breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) - breach_time : time of last breach in milliseconds since boot (uint32_t) - - ''' - return self.send(self.fence_status_encode(breach_status, breach_count, breach_type, breach_time)) - - def ahrs_encode(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): - ''' - Status of DCM attitude estimator - - omegaIx : X gyro drift estimate rad/s (float) - omegaIy : Y gyro drift estimate rad/s (float) - omegaIz : Z gyro drift estimate rad/s (float) - accel_weight : average accel_weight (float) - renorm_val : average renormalisation value (float) - error_rp : average error_roll_pitch value (float) - error_yaw : average error_yaw value (float) - - ''' - msg = MAVLink_ahrs_message(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw) - msg.pack(self) - return msg - - def ahrs_send(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): - ''' - Status of DCM attitude estimator - - omegaIx : X gyro drift estimate rad/s (float) - omegaIy : Y gyro drift estimate rad/s (float) - omegaIz : Z gyro drift estimate rad/s (float) - accel_weight : average accel_weight (float) - renorm_val : average renormalisation value (float) - error_rp : average error_roll_pitch value (float) - error_yaw : average error_yaw value (float) - - ''' - return self.send(self.ahrs_encode(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw)) - - def simstate_encode(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro): - ''' - Status of simulation environment, if used - - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - xacc : X acceleration m/s/s (float) - yacc : Y acceleration m/s/s (float) - zacc : Z acceleration m/s/s (float) - xgyro : Angular speed around X axis rad/s (float) - ygyro : Angular speed around Y axis rad/s (float) - zgyro : Angular speed around Z axis rad/s (float) - - ''' - msg = MAVLink_simstate_message(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro) - msg.pack(self) - return msg - - def simstate_send(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro): - ''' - Status of simulation environment, if used - - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - xacc : X acceleration m/s/s (float) - yacc : Y acceleration m/s/s (float) - zacc : Z acceleration m/s/s (float) - xgyro : Angular speed around X axis rad/s (float) - ygyro : Angular speed around Y axis rad/s (float) - zgyro : Angular speed around Z axis rad/s (float) - - ''' - return self.send(self.simstate_encode(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro)) - - def hwstatus_encode(self, Vcc, I2Cerr): - ''' - Status of key hardware - - Vcc : board voltage (mV) (uint16_t) - I2Cerr : I2C error count (uint8_t) - - ''' - msg = MAVLink_hwstatus_message(Vcc, I2Cerr) - msg.pack(self) - return msg - - def hwstatus_send(self, Vcc, I2Cerr): - ''' - Status of key hardware - - Vcc : board voltage (mV) (uint16_t) - I2Cerr : I2C error count (uint8_t) - - ''' - return self.send(self.hwstatus_encode(Vcc, I2Cerr)) - - def radio_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): - ''' - Status generated by radio - - rssi : local signal strength (uint8_t) - remrssi : remote signal strength (uint8_t) - txbuf : how full the tx buffer is as a percentage (uint8_t) - noise : background noise level (uint8_t) - remnoise : remote background noise level (uint8_t) - rxerrors : receive errors (uint16_t) - fixed : count of error corrected packets (uint16_t) - - ''' - msg = MAVLink_radio_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) - msg.pack(self) - return msg - - def radio_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): - ''' - Status generated by radio - - rssi : local signal strength (uint8_t) - remrssi : remote signal strength (uint8_t) - txbuf : how full the tx buffer is as a percentage (uint8_t) - noise : background noise level (uint8_t) - remnoise : remote background noise level (uint8_t) - rxerrors : receive errors (uint16_t) - fixed : count of error corrected packets (uint16_t) - - ''' - return self.send(self.radio_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) - - def heartbeat_encode(self, type, autopilot, mavlink_version=2): - ''' - 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). - - type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) - autopilot : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t) - mavlink_version : MAVLink version (uint8_t) - - ''' - msg = MAVLink_heartbeat_message(type, autopilot, mavlink_version) - msg.pack(self) - return msg - - def heartbeat_send(self, type, autopilot, mavlink_version=2): - ''' - 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). - - type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) - autopilot : Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM (uint8_t) - mavlink_version : MAVLink version (uint8_t) - - ''' - return self.send(self.heartbeat_encode(type, autopilot, mavlink_version)) - - def boot_encode(self, version): - ''' - The boot message indicates that a system is starting. The onboard - software version allows to keep track of onboard - soft/firmware revisions. - - version : The onboard software version (uint32_t) - - ''' - msg = MAVLink_boot_message(version) - msg.pack(self) - return msg - - def boot_send(self, version): - ''' - The boot message indicates that a system is starting. The onboard - software version allows to keep track of onboard - soft/firmware revisions. - - version : The onboard software version (uint32_t) - - ''' - return self.send(self.boot_encode(version)) - - def system_time_encode(self, time_usec): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - - time_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) - - ''' - msg = MAVLink_system_time_message(time_usec) - msg.pack(self) - return msg - - def system_time_send(self, time_usec): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - - time_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) - - ''' - return self.send(self.system_time_encode(time_usec)) - - def ping_encode(self, seq, target_system, target_component, time): - ''' - A ping message either requesting or responding to a ping. This allows - to measure the system latencies, including serial - port, radio modem and UDP connections. - - seq : PING sequence (uint32_t) - target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - time : Unix timestamp in microseconds (uint64_t) - - ''' - msg = MAVLink_ping_message(seq, target_system, target_component, time) - msg.pack(self) - return msg - - def ping_send(self, seq, target_system, target_component, time): - ''' - A ping message either requesting or responding to a ping. This allows - to measure the system latencies, including serial - port, radio modem and UDP connections. - - seq : PING sequence (uint32_t) - target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - time : Unix timestamp in microseconds (uint64_t) - - ''' - return self.send(self.ping_encode(seq, target_system, target_component, time)) - - def system_time_utc_encode(self, utc_date, utc_time): - ''' - UTC date and time from GPS module - - utc_date : GPS UTC date ddmmyy (uint32_t) - utc_time : GPS UTC time hhmmss (uint32_t) - - ''' - msg = MAVLink_system_time_utc_message(utc_date, utc_time) - msg.pack(self) - return msg - - def system_time_utc_send(self, utc_date, utc_time): - ''' - UTC date and time from GPS module - - utc_date : GPS UTC date ddmmyy (uint32_t) - utc_time : GPS UTC time hhmmss (uint32_t) - - ''' - return self.send(self.system_time_utc_encode(utc_date, utc_time)) - - def change_operator_control_encode(self, target_system, control_request, version, passkey): - ''' - Request to control this MAV - - target_system : System the GCS requests control for (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) - passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) - - ''' - msg = MAVLink_change_operator_control_message(target_system, control_request, version, passkey) - msg.pack(self) - return msg - - def change_operator_control_send(self, target_system, control_request, version, passkey): - ''' - Request to control this MAV - - target_system : System the GCS requests control for (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) - passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) - - ''' - return self.send(self.change_operator_control_encode(target_system, control_request, version, passkey)) - - def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack): - ''' - Accept / deny control of this MAV - - gcs_system_id : ID of the GCS this message (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) - - ''' - msg = MAVLink_change_operator_control_ack_message(gcs_system_id, control_request, ack) - msg.pack(self) - return msg - - def change_operator_control_ack_send(self, gcs_system_id, control_request, ack): - ''' - Accept / deny control of this MAV - - gcs_system_id : ID of the GCS this message (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) - - ''' - return self.send(self.change_operator_control_ack_encode(gcs_system_id, control_request, ack)) - - def auth_key_encode(self, key): - ''' - Emit an encrypted signature / key identifying this system. PLEASE - NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for - true safety. - - key : key (char) - - ''' - msg = MAVLink_auth_key_message(key) - msg.pack(self) - return msg - - def auth_key_send(self, key): - ''' - Emit an encrypted signature / key identifying this system. PLEASE - NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for - true safety. - - key : key (char) - - ''' - return self.send(self.auth_key_encode(key)) - - def action_ack_encode(self, action, result): - ''' - This message acknowledges an action. IMPORTANT: The acknowledgement - can be also negative, e.g. the MAV rejects a reset - message because it is in-flight. The action ids are - defined in ENUM MAV_ACTION in - mavlink/include/mavlink_types.h - - action : The action id (uint8_t) - result : 0: Action DENIED, 1: Action executed (uint8_t) - - ''' - msg = MAVLink_action_ack_message(action, result) - msg.pack(self) - return msg - - def action_ack_send(self, action, result): - ''' - This message acknowledges an action. IMPORTANT: The acknowledgement - can be also negative, e.g. the MAV rejects a reset - message because it is in-flight. The action ids are - defined in ENUM MAV_ACTION in - mavlink/include/mavlink_types.h - - action : The action id (uint8_t) - result : 0: Action DENIED, 1: Action executed (uint8_t) - - ''' - return self.send(self.action_ack_encode(action, result)) - - def action_encode(self, target, target_component, action): - ''' - An action message allows to execute a certain onboard action. These - include liftoff, land, storing parameters too EEPROM, - shutddown, etc. The action ids are defined in ENUM - MAV_ACTION in mavlink/include/mavlink_types.h - - target : The system executing the action (uint8_t) - target_component : The component executing the action (uint8_t) - action : The action id (uint8_t) - - ''' - msg = MAVLink_action_message(target, target_component, action) - msg.pack(self) - return msg - - def action_send(self, target, target_component, action): - ''' - An action message allows to execute a certain onboard action. These - include liftoff, land, storing parameters too EEPROM, - shutddown, etc. The action ids are defined in ENUM - MAV_ACTION in mavlink/include/mavlink_types.h - - target : The system executing the action (uint8_t) - target_component : The component executing the action (uint8_t) - action : The action id (uint8_t) - - ''' - return self.send(self.action_encode(target, target_component, action)) - - def set_mode_encode(self, target, mode): - ''' - Set the system mode, as defined by enum MAV_MODE in - mavlink/include/mavlink_types.h. There is no target - component id as the mode is by definition for the - overall aircraft, not only for one component. - - target : The system setting the mode (uint8_t) - mode : The new mode (uint8_t) - - ''' - msg = MAVLink_set_mode_message(target, mode) - msg.pack(self) - return msg - - def set_mode_send(self, target, mode): - ''' - Set the system mode, as defined by enum MAV_MODE in - mavlink/include/mavlink_types.h. There is no target - component id as the mode is by definition for the - overall aircraft, not only for one component. - - target : The system setting the mode (uint8_t) - mode : The new mode (uint8_t) - - ''' - return self.send(self.set_mode_encode(target, mode)) - - def set_nav_mode_encode(self, target, nav_mode): - ''' - Set the system navigation mode, as defined by enum MAV_NAV_MODE in - mavlink/include/mavlink_types.h. The navigation mode - applies to the whole aircraft and thus all components. - - target : The system setting the mode (uint8_t) - nav_mode : The new navigation mode (uint8_t) - - ''' - msg = MAVLink_set_nav_mode_message(target, nav_mode) - msg.pack(self) - return msg - - def set_nav_mode_send(self, target, nav_mode): - ''' - Set the system navigation mode, as defined by enum MAV_NAV_MODE in - mavlink/include/mavlink_types.h. The navigation mode - applies to the whole aircraft and thus all components. - - target : The system setting the mode (uint8_t) - nav_mode : The new navigation mode (uint8_t) - - ''' - return self.send(self.set_nav_mode_encode(target, nav_mode)) - - def param_request_read_encode(self, target_system, target_component, param_id, param_index): - ''' - Request to read the onboard parameter with the param_id string id. - Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any - other component (such as the GCS) without the need of - previous knowledge of possible parameter names. Thus - the same GCS can store different parameters for - different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a - full documentation of QGroundControl and IMU code. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (int8_t) - param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) - - ''' - msg = MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) - msg.pack(self) - return msg - - def param_request_read_send(self, target_system, target_component, param_id, param_index): - ''' - Request to read the onboard parameter with the param_id string id. - Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any - other component (such as the GCS) without the need of - previous knowledge of possible parameter names. Thus - the same GCS can store different parameters for - different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a - full documentation of QGroundControl and IMU code. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (int8_t) - param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) - - ''' - return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) - - def param_request_list_encode(self, target_system, target_component): - ''' - Request all parameters of this component. After his request, all - parameters are emitted. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_param_request_list_message(target_system, target_component) - msg.pack(self) - return msg - - def param_request_list_send(self, target_system, target_component): - ''' - Request all parameters of this component. After his request, all - parameters are emitted. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.param_request_list_encode(target_system, target_component)) - - def param_value_encode(self, param_id, param_value, param_count, param_index): - ''' - Emit the value of a onboard parameter. The inclusion of param_count - and param_index in the message allows the recipient to - keep track of received parameters and allows him to - re-request missing parameters after a loss or timeout. - - param_id : Onboard parameter id (int8_t) - param_value : Onboard parameter value (float) - param_count : Total number of onboard parameters (uint16_t) - param_index : Index of this onboard parameter (uint16_t) - - ''' - msg = MAVLink_param_value_message(param_id, param_value, param_count, param_index) - msg.pack(self) - return msg - - def param_value_send(self, param_id, param_value, param_count, param_index): - ''' - Emit the value of a onboard parameter. The inclusion of param_count - and param_index in the message allows the recipient to - keep track of received parameters and allows him to - re-request missing parameters after a loss or timeout. - - param_id : Onboard parameter id (int8_t) - param_value : Onboard parameter value (float) - param_count : Total number of onboard parameters (uint16_t) - param_index : Index of this onboard parameter (uint16_t) - - ''' - return self.send(self.param_value_encode(param_id, param_value, param_count, param_index)) - - def param_set_encode(self, target_system, target_component, param_id, param_value): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to default - on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM - contents to EEPROM. IMPORTANT: The receiving component - should acknowledge the new parameter value by sending - a param_value message to all communication partners. - This will also ensure that multiple GCS all have an - up-to-date list of all parameters. If the sending GCS - did not receive a PARAM_VALUE message within its - timeout time, it should re-send the PARAM_SET message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (int8_t) - param_value : Onboard parameter value (float) - - ''' - msg = MAVLink_param_set_message(target_system, target_component, param_id, param_value) - msg.pack(self) - return msg - - def param_set_send(self, target_system, target_component, param_id, param_value): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to default - on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM - contents to EEPROM. IMPORTANT: The receiving component - should acknowledge the new parameter value by sending - a param_value message to all communication partners. - This will also ensure that multiple GCS all have an - up-to-date list of all parameters. If the sending GCS - did not receive a PARAM_VALUE message within its - timeout time, it should re-send the PARAM_SET message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (int8_t) - param_value : Onboard parameter value (float) - - ''' - return self.send(self.param_set_encode(target_system, target_component, param_id, param_value)) - - def gps_raw_int_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in 1E7 degrees (int32_t) - lon : Longitude in 1E7 degrees (int32_t) - alt : Altitude in 1E3 meters (millimeters) (int32_t) - eph : GPS HDOP (float) - epv : GPS VDOP (float) - v : GPS ground speed (m/s) (float) - hdg : Compass heading in degrees, 0..360 degrees (float) - - ''' - msg = MAVLink_gps_raw_int_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) - msg.pack(self) - return msg - - def gps_raw_int_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in 1E7 degrees (int32_t) - lon : Longitude in 1E7 degrees (int32_t) - alt : Altitude in 1E3 meters (millimeters) (int32_t) - eph : GPS HDOP (float) - epv : GPS VDOP (float) - v : GPS ground speed (m/s) (float) - hdg : Compass heading in degrees, 0..360 degrees (float) - - ''' - return self.send(self.gps_raw_int_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) - - def scaled_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should contain the scaled values to the described - units - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - xgyro : Angular speed around X axis (millirad /sec) (int16_t) - ygyro : Angular speed around Y axis (millirad /sec) (int16_t) - zgyro : Angular speed around Z axis (millirad /sec) (int16_t) - xmag : X Magnetic field (milli tesla) (int16_t) - ymag : Y Magnetic field (milli tesla) (int16_t) - zmag : Z Magnetic field (milli tesla) (int16_t) - - ''' - msg = MAVLink_scaled_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) - msg.pack(self) - return msg - - def scaled_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should contain the scaled values to the described - units - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - xgyro : Angular speed around X axis (millirad /sec) (int16_t) - ygyro : Angular speed around Y axis (millirad /sec) (int16_t) - zgyro : Angular speed around Z axis (millirad /sec) (int16_t) - xmag : X Magnetic field (milli tesla) (int16_t) - ymag : Y Magnetic field (milli tesla) (int16_t) - zmag : Z Magnetic field (milli tesla) (int16_t) - - ''' - return self.send(self.scaled_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) - - def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - ''' - The positioning status, as reported by GPS. This message is intended - to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION - for the global position estimate. This message can - contain information for up to 20 satellites. - - satellites_visible : Number of satellites visible (uint8_t) - satellite_prn : Global satellite ID (int8_t) - satellite_used : 0: Satellite not used, 1: used for localization (int8_t) - satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) - satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) - satellite_snr : Signal to noise ratio of satellite (int8_t) - - ''' - msg = MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) - msg.pack(self) - return msg - - def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - ''' - The positioning status, as reported by GPS. This message is intended - to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION - for the global position estimate. This message can - contain information for up to 20 satellites. - - satellites_visible : Number of satellites visible (uint8_t) - satellite_prn : Global satellite ID (int8_t) - satellite_used : 0: Satellite not used, 1: used for localization (int8_t) - satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (int8_t) - satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (int8_t) - satellite_snr : Signal to noise ratio of satellite (int8_t) - - ''' - return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) - - def raw_imu_encode(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should always contain the true raw values without any - scaling to allow data capture and system debugging. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (raw) (int16_t) - yacc : Y acceleration (raw) (int16_t) - zacc : Z acceleration (raw) (int16_t) - xgyro : Angular speed around X axis (raw) (int16_t) - ygyro : Angular speed around Y axis (raw) (int16_t) - zgyro : Angular speed around Z axis (raw) (int16_t) - xmag : X Magnetic field (raw) (int16_t) - ymag : Y Magnetic field (raw) (int16_t) - zmag : Z Magnetic field (raw) (int16_t) - - ''' - msg = MAVLink_raw_imu_message(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) - msg.pack(self) - return msg - - def raw_imu_send(self, usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should always contain the true raw values without any - scaling to allow data capture and system debugging. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (raw) (int16_t) - yacc : Y acceleration (raw) (int16_t) - zacc : Z acceleration (raw) (int16_t) - xgyro : Angular speed around X axis (raw) (int16_t) - ygyro : Angular speed around Y axis (raw) (int16_t) - zgyro : Angular speed around Z axis (raw) (int16_t) - xmag : X Magnetic field (raw) (int16_t) - ymag : Y Magnetic field (raw) (int16_t) - zmag : Z Magnetic field (raw) (int16_t) - - ''' - return self.send(self.raw_imu_encode(usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) - - def raw_pressure_encode(self, usec, press_abs, press_diff1, press_diff2, temperature): - ''' - The RAW pressure readings for the typical setup of one absolute - pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (raw) (int16_t) - press_diff1 : Differential pressure 1 (raw) (int16_t) - press_diff2 : Differential pressure 2 (raw) (int16_t) - temperature : Raw Temperature measurement (raw) (int16_t) - - ''' - msg = MAVLink_raw_pressure_message(usec, press_abs, press_diff1, press_diff2, temperature) - msg.pack(self) - return msg - - def raw_pressure_send(self, usec, press_abs, press_diff1, press_diff2, temperature): - ''' - The RAW pressure readings for the typical setup of one absolute - pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (raw) (int16_t) - press_diff1 : Differential pressure 1 (raw) (int16_t) - press_diff2 : Differential pressure 2 (raw) (int16_t) - temperature : Raw Temperature measurement (raw) (int16_t) - - ''' - return self.send(self.raw_pressure_encode(usec, press_abs, press_diff1, press_diff2, temperature)) - - def scaled_pressure_encode(self, usec, press_abs, press_diff, temperature): - ''' - The pressure readings for the typical setup of one absolute and - differential pressure sensor. The units are as - specified in each field. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (hectopascal) (float) - press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) - - ''' - msg = MAVLink_scaled_pressure_message(usec, press_abs, press_diff, temperature) - msg.pack(self) - return msg - - def scaled_pressure_send(self, usec, press_abs, press_diff, temperature): - ''' - The pressure readings for the typical setup of one absolute and - differential pressure sensor. The units are as - specified in each field. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (hectopascal) (float) - press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) - - ''' - return self.send(self.scaled_pressure_encode(usec, press_abs, press_diff, temperature)) - - def attitude_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right). - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - msg = MAVLink_attitude_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) - msg.pack(self) - return msg - - def attitude_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right). - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - return self.send(self.attitude_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) - - def local_position_encode(self, usec, x, y, z, vx, vy, vz): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, - Z-axis down (aeronautical frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - x : X Position (float) - y : Y Position (float) - z : Z Position (float) - vx : X Speed (float) - vy : Y Speed (float) - vz : Z Speed (float) - - ''' - msg = MAVLink_local_position_message(usec, x, y, z, vx, vy, vz) - msg.pack(self) - return msg - - def local_position_send(self, usec, x, y, z, vx, vy, vz): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, - Z-axis down (aeronautical frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - x : X Position (float) - y : Y Position (float) - z : Z Position (float) - vx : X Speed (float) - vy : Y Speed (float) - vz : Z Speed (float) - - ''' - return self.send(self.local_position_encode(usec, x, y, z, vx, vy, vz)) - - def global_position_encode(self, usec, lat, lon, alt, vx, vy, vz): - ''' - The filtered global position (e.g. fused GPS and accelerometers). - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since unix epoch) (uint64_t) - lat : Latitude, in degrees (float) - lon : Longitude, in degrees (float) - alt : Absolute altitude, in meters (float) - vx : X Speed (in Latitude direction, positive: going north) (float) - vy : Y Speed (in Longitude direction, positive: going east) (float) - vz : Z Speed (in Altitude direction, positive: going up) (float) - - ''' - msg = MAVLink_global_position_message(usec, lat, lon, alt, vx, vy, vz) - msg.pack(self) - return msg - - def global_position_send(self, usec, lat, lon, alt, vx, vy, vz): - ''' - The filtered global position (e.g. fused GPS and accelerometers). - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since unix epoch) (uint64_t) - lat : Latitude, in degrees (float) - lon : Longitude, in degrees (float) - alt : Absolute altitude, in meters (float) - vx : X Speed (in Latitude direction, positive: going north) (float) - vy : Y Speed (in Longitude direction, positive: going east) (float) - vz : Z Speed (in Altitude direction, positive: going up) (float) - - ''' - return self.send(self.global_position_encode(usec, lat, lon, alt, vx, vy, vz)) - - def gps_raw_encode(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in degrees (float) - lon : Longitude in degrees (float) - alt : Altitude in meters (float) - eph : GPS HDOP (float) - epv : GPS VDOP (float) - v : GPS ground speed (float) - hdg : Compass heading in degrees, 0..360 degrees (float) - - ''' - msg = MAVLink_gps_raw_message(usec, fix_type, lat, lon, alt, eph, epv, v, hdg) - msg.pack(self) - return msg - - def gps_raw_send(self, usec, fix_type, lat, lon, alt, eph, epv, v, hdg): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position estimate of the - sytem, but rather a RAW sensor value. See message - GLOBAL_POSITION for the global position estimate. - Coordinate frame is right-handed, Z-axis up (GPS - frame) - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in degrees (float) - lon : Longitude in degrees (float) - alt : Altitude in meters (float) - eph : GPS HDOP (float) - epv : GPS VDOP (float) - v : GPS ground speed (float) - hdg : Compass heading in degrees, 0..360 degrees (float) - - ''' - return self.send(self.gps_raw_encode(usec, fix_type, lat, lon, alt, eph, epv, v, hdg)) - - def sys_status_encode(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): - ''' - The general system state. If the system is following the MAVLink - standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is - either LOCKED (motors shut down and locked), MANUAL - (system under RC control), GUIDED (system with - autonomous position control, position setpoint - controlled manually) or AUTO (system guided by - path/waypoint planner). The NAV_MODE defined the - current flight state: LIFTOFF (often an open-loop - maneuver), LANDING, WAYPOINTS or VECTOR. This - represents the internal navigation state machine. The - system status shows wether the system is currently - active or not and if an emergency occured. During the - CRITICAL and EMERGENCY states the MAV is still - considered to be active, but should start emergency - procedures autonomously. After a failure occured it - should first move from active to critical to allow - manual intervention and then move to emergency after a - certain timeout. - - mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) - nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) - status : System status flag, see MAV_STATUS ENUM (uint8_t) - load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) - vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) - battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) - packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) - - ''' - msg = MAVLink_sys_status_message(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop) - msg.pack(self) - return msg - - def sys_status_send(self, mode, nav_mode, status, load, vbat, battery_remaining, packet_drop): - ''' - The general system state. If the system is following the MAVLink - standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is - either LOCKED (motors shut down and locked), MANUAL - (system under RC control), GUIDED (system with - autonomous position control, position setpoint - controlled manually) or AUTO (system guided by - path/waypoint planner). The NAV_MODE defined the - current flight state: LIFTOFF (often an open-loop - maneuver), LANDING, WAYPOINTS or VECTOR. This - represents the internal navigation state machine. The - system status shows wether the system is currently - active or not and if an emergency occured. During the - CRITICAL and EMERGENCY states the MAV is still - considered to be active, but should start emergency - procedures autonomously. After a failure occured it - should first move from active to critical to allow - manual intervention and then move to emergency after a - certain timeout. - - mode : System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h (uint8_t) - nav_mode : Navigation mode, see MAV_NAV_MODE ENUM (uint8_t) - status : System status flag, see MAV_STATUS ENUM (uint8_t) - load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) - vbat : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) - battery_remaining : Remaining battery energy: (0%: 0, 100%: 1000) (uint16_t) - packet_drop : Dropped packets (packets that were corrupted on reception on the MAV) (uint16_t) - - ''' - return self.send(self.sys_status_encode(mode, nav_mode, status, load, vbat, battery_remaining, packet_drop)) - - def rc_channels_raw_encode(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters - might violate this specification. - - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_rc_channels_raw_message(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) - msg.pack(self) - return msg - - def rc_channels_raw_send(self, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters - might violate this specification. - - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.rc_channels_raw_encode(chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) - - def rc_channels_scaled_encode(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - ''' - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, - (100%) 10000 - - chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_rc_channels_scaled_message(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) - msg.pack(self) - return msg - - def rc_channels_scaled_send(self, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - ''' - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, - (100%) 10000 - - chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.rc_channels_scaled_encode(chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) - - def servo_output_raw_encode(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - ''' - The RAW values of the servo outputs (for RC input from the remote, use - the RC_CHANNELS messages). The standard PPM modulation - is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - - servo1_raw : Servo output 1 value, in microseconds (uint16_t) - servo2_raw : Servo output 2 value, in microseconds (uint16_t) - servo3_raw : Servo output 3 value, in microseconds (uint16_t) - servo4_raw : Servo output 4 value, in microseconds (uint16_t) - servo5_raw : Servo output 5 value, in microseconds (uint16_t) - servo6_raw : Servo output 6 value, in microseconds (uint16_t) - servo7_raw : Servo output 7 value, in microseconds (uint16_t) - servo8_raw : Servo output 8 value, in microseconds (uint16_t) - - ''' - msg = MAVLink_servo_output_raw_message(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) - msg.pack(self) - return msg - - def servo_output_raw_send(self, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - ''' - The RAW values of the servo outputs (for RC input from the remote, use - the RC_CHANNELS messages). The standard PPM modulation - is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - - servo1_raw : Servo output 1 value, in microseconds (uint16_t) - servo2_raw : Servo output 2 value, in microseconds (uint16_t) - servo3_raw : Servo output 3 value, in microseconds (uint16_t) - servo4_raw : Servo output 4 value, in microseconds (uint16_t) - servo5_raw : Servo output 5 value, in microseconds (uint16_t) - servo6_raw : Servo output 6 value, in microseconds (uint16_t) - servo7_raw : Servo output 7 value, in microseconds (uint16_t) - servo8_raw : Servo output 8 value, in microseconds (uint16_t) - - ''' - return self.send(self.servo_output_raw_encode(servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) - - def waypoint_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - ''' - Message encoding a waypoint. This message is emitted to announce - the presence of a waypoint and to set a waypoint on - the system. The waypoint can be either in x, y, z - meters (type: LOCAL) or x:lat, y:lon, z:altitude. - Local frame is Z-down, right handed, global frame is - Z-up, right handed - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) - command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) - current : false:0, true:1 (uint8_t) - autocontinue : autocontinue to next wp (uint8_t) - param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) - param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) - param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) - param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) - x : PARAM5 / local: x position, global: latitude (float) - y : PARAM6 / y position: global: longitude (float) - z : PARAM7 / z position: global: altitude (float) - - ''' - msg = MAVLink_waypoint_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) - msg.pack(self) - return msg - - def waypoint_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - ''' - Message encoding a waypoint. This message is emitted to announce - the presence of a waypoint and to set a waypoint on - the system. The waypoint can be either in x, y, z - meters (type: LOCAL) or x:lat, y:lon, z:altitude. - Local frame is Z-down, right handed, global frame is - Z-up, right handed - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - frame : The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h (uint8_t) - command : The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs (uint8_t) - current : false:0, true:1 (uint8_t) - autocontinue : autocontinue to next wp (uint8_t) - param1 : PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters (float) - param2 : PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) - param3 : PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) - param4 : PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH (float) - x : PARAM5 / local: x position, global: latitude (float) - y : PARAM6 / y position: global: longitude (float) - z : PARAM7 / z position: global: altitude (float) - - ''' - return self.send(self.waypoint_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) - - def waypoint_request_encode(self, target_system, target_component, seq): - ''' - Request the information of the waypoint with the sequence number seq. - The response of the system to this message should be a - WAYPOINT message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_request_message(target_system, target_component, seq) - msg.pack(self) - return msg - - def waypoint_request_send(self, target_system, target_component, seq): - ''' - Request the information of the waypoint with the sequence number seq. - The response of the system to this message should be a - WAYPOINT message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - return self.send(self.waypoint_request_encode(target_system, target_component, seq)) - - def waypoint_set_current_encode(self, target_system, target_component, seq): - ''' - Set the waypoint with sequence number seq as current waypoint. This - means that the MAV will continue to this waypoint on - the shortest path (not following the waypoints in- - between). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_set_current_message(target_system, target_component, seq) - msg.pack(self) - return msg - - def waypoint_set_current_send(self, target_system, target_component, seq): - ''' - Set the waypoint with sequence number seq as current waypoint. This - means that the MAV will continue to this waypoint on - the shortest path (not following the waypoints in- - between). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - return self.send(self.waypoint_set_current_encode(target_system, target_component, seq)) - - def waypoint_current_encode(self, seq): - ''' - Message that announces the sequence number of the current active - waypoint. The MAV will fly towards this waypoint. - - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_current_message(seq) - msg.pack(self) - return msg - - def waypoint_current_send(self, seq): - ''' - Message that announces the sequence number of the current active - waypoint. The MAV will fly towards this waypoint. - - seq : Sequence (uint16_t) - - ''' - return self.send(self.waypoint_current_encode(seq)) - - def waypoint_request_list_encode(self, target_system, target_component): - ''' - Request the overall list of waypoints from the system/component. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_waypoint_request_list_message(target_system, target_component) - msg.pack(self) - return msg - - def waypoint_request_list_send(self, target_system, target_component): - ''' - Request the overall list of waypoints from the system/component. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.waypoint_request_list_encode(target_system, target_component)) - - def waypoint_count_encode(self, target_system, target_component, count): - ''' - This message is emitted as response to WAYPOINT_REQUEST_LIST by the - MAV. The GCS can then request the individual waypoints - based on the knowledge of the total number of - waypoints. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - count : Number of Waypoints in the Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_count_message(target_system, target_component, count) - msg.pack(self) - return msg - - def waypoint_count_send(self, target_system, target_component, count): - ''' - This message is emitted as response to WAYPOINT_REQUEST_LIST by the - MAV. The GCS can then request the individual waypoints - based on the knowledge of the total number of - waypoints. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - count : Number of Waypoints in the Sequence (uint16_t) - - ''' - return self.send(self.waypoint_count_encode(target_system, target_component, count)) - - def waypoint_clear_all_encode(self, target_system, target_component): - ''' - Delete all waypoints at once. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_waypoint_clear_all_message(target_system, target_component) - msg.pack(self) - return msg - - def waypoint_clear_all_send(self, target_system, target_component): - ''' - Delete all waypoints at once. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.waypoint_clear_all_encode(target_system, target_component)) - - def waypoint_reached_encode(self, seq): - ''' - A certain waypoint has been reached. The system will either hold this - position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next - waypoint. - - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_waypoint_reached_message(seq) - msg.pack(self) - return msg - - def waypoint_reached_send(self, seq): - ''' - A certain waypoint has been reached. The system will either hold this - position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next - waypoint. - - seq : Sequence (uint16_t) - - ''' - return self.send(self.waypoint_reached_encode(seq)) - - def waypoint_ack_encode(self, target_system, target_component, type): - ''' - Ack message during waypoint handling. The type field states if this - message is a positive ack (type=0) or if an error - happened (type=non-zero). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - type : 0: OK, 1: Error (uint8_t) - - ''' - msg = MAVLink_waypoint_ack_message(target_system, target_component, type) - msg.pack(self) - return msg - - def waypoint_ack_send(self, target_system, target_component, type): - ''' - Ack message during waypoint handling. The type field states if this - message is a positive ack (type=0) or if an error - happened (type=non-zero). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - type : 0: OK, 1: Error (uint8_t) - - ''' - return self.send(self.waypoint_ack_encode(target_system, target_component, type)) - - def gps_set_global_origin_encode(self, target_system, target_component, latitude, longitude, altitude): - ''' - As local waypoints exist, the global waypoint reference allows to - transform between the local coordinate frame and the - global (GPS) coordinate frame. This can be necessary - when e.g. in- and outdoor settings are connected and - the MAV should move from in- to outdoor. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - latitude : global position * 1E7 (int32_t) - longitude : global position * 1E7 (int32_t) - altitude : global position * 1000 (int32_t) - - ''' - msg = MAVLink_gps_set_global_origin_message(target_system, target_component, latitude, longitude, altitude) - msg.pack(self) - return msg - - def gps_set_global_origin_send(self, target_system, target_component, latitude, longitude, altitude): - ''' - As local waypoints exist, the global waypoint reference allows to - transform between the local coordinate frame and the - global (GPS) coordinate frame. This can be necessary - when e.g. in- and outdoor settings are connected and - the MAV should move from in- to outdoor. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - latitude : global position * 1E7 (int32_t) - longitude : global position * 1E7 (int32_t) - altitude : global position * 1000 (int32_t) - - ''' - return self.send(self.gps_set_global_origin_encode(target_system, target_component, latitude, longitude, altitude)) - - def gps_local_origin_set_encode(self, latitude, longitude, altitude): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - - latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) - longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) - altitude : Altitude(WGS84), expressed as * 1000 (int32_t) - - ''' - msg = MAVLink_gps_local_origin_set_message(latitude, longitude, altitude) - msg.pack(self) - return msg - - def gps_local_origin_set_send(self, latitude, longitude, altitude): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - - latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) - longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) - altitude : Altitude(WGS84), expressed as * 1000 (int32_t) - - ''' - return self.send(self.gps_local_origin_set_encode(latitude, longitude, altitude)) - - def local_position_setpoint_set_encode(self, target_system, target_component, x, y, z, yaw): - ''' - Set the setpoint for a local position controller. This is the position - in local coordinates the MAV should fly to. This - message is sent by the path/waypoint planner to the - onboard position controller. As some MAVs have a - degree of freedom in yaw (e.g. all - helicopters/quadrotors), the desired yaw angle is part - of the message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - msg = MAVLink_local_position_setpoint_set_message(target_system, target_component, x, y, z, yaw) - msg.pack(self) - return msg - - def local_position_setpoint_set_send(self, target_system, target_component, x, y, z, yaw): - ''' - Set the setpoint for a local position controller. This is the position - in local coordinates the MAV should fly to. This - message is sent by the path/waypoint planner to the - onboard position controller. As some MAVs have a - degree of freedom in yaw (e.g. all - helicopters/quadrotors), the desired yaw angle is part - of the message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - return self.send(self.local_position_setpoint_set_encode(target_system, target_component, x, y, z, yaw)) - - def local_position_setpoint_encode(self, x, y, z, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - msg = MAVLink_local_position_setpoint_message(x, y, z, yaw) - msg.pack(self) - return msg - - def local_position_setpoint_send(self, x, y, z, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - return self.send(self.local_position_setpoint_encode(x, y, z, yaw)) - - def control_status_encode(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): - ''' - - - position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) - vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) - gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) - ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) - control_att : 0: Attitude control disabled, 1: enabled (uint8_t) - control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) - control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) - control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) - - ''' - msg = MAVLink_control_status_message(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw) - msg.pack(self) - return msg - - def control_status_send(self, position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw): - ''' - - - position_fix : Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix (uint8_t) - vision_fix : Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix (uint8_t) - gps_fix : GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix (uint8_t) - ahrs_health : Attitude estimation health: 0: poor, 255: excellent (uint8_t) - control_att : 0: Attitude control disabled, 1: enabled (uint8_t) - control_pos_xy : 0: X, Y position control disabled, 1: enabled (uint8_t) - control_pos_z : 0: Z position control disabled, 1: enabled (uint8_t) - control_pos_yaw : 0: Yaw angle control disabled, 1: enabled (uint8_t) - - ''' - return self.send(self.control_status_encode(position_fix, vision_fix, gps_fix, ahrs_health, control_att, control_pos_xy, control_pos_z, control_pos_yaw)) - - def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Set a safety zone (volume), which is defined by two corners of a cube. - This message can be used to tell the MAV which - setpoints/waypoints to accept and which to reject. - Safety areas are often enforced by national or - competition regulations. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - msg = MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) - msg.pack(self) - return msg - - def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Set a safety zone (volume), which is defined by two corners of a cube. - This message can be used to tell the MAV which - setpoints/waypoints to accept and which to reject. - Safety areas are often enforced by national or - competition regulations. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) - - def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Read out the safety zone the MAV currently assumes. - - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - msg = MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) - msg.pack(self) - return msg - - def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Read out the safety zone the MAV currently assumes. - - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) - - def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust) - msg.pack(self) - return msg - - def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust)) - - def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust) - msg.pack(self) - return msg - - def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)) - - def roll_pitch_yaw_thrust_setpoint_encode(self, time_us, roll, pitch, yaw, thrust): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - - time_us : Timestamp in micro seconds since unix epoch (uint64_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_us, roll, pitch, yaw, thrust) - msg.pack(self) - return msg - - def roll_pitch_yaw_thrust_setpoint_send(self, time_us, roll, pitch, yaw, thrust): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - - time_us : Timestamp in micro seconds since unix epoch (uint64_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_us, roll, pitch, yaw, thrust)) - - def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active on the - system. - - time_us : Timestamp in micro seconds since unix epoch (uint64_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_us, roll_speed, pitch_speed, yaw_speed, thrust) - msg.pack(self) - return msg - - def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_us, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active on the - system. - - time_us : Timestamp in micro seconds since unix epoch (uint64_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_us, roll_speed, pitch_speed, yaw_speed, thrust)) - - def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - ''' - Outputs of the APM navigation controller. The primary use of this - message is to check the response and signs of the - controller before actual flight and to assist with - tuning controller parameters - - nav_roll : Current desired roll in degrees (float) - nav_pitch : Current desired pitch in degrees (float) - nav_bearing : Current desired heading in degrees (int16_t) - target_bearing : Bearing to current waypoint/target in degrees (int16_t) - wp_dist : Distance to active waypoint in meters (uint16_t) - alt_error : Current altitude error in meters (float) - aspd_error : Current airspeed error in meters/second (float) - xtrack_error : Current crosstrack error on x-y plane in meters (float) - - ''' - msg = MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) - msg.pack(self) - return msg - - def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - ''' - Outputs of the APM navigation controller. The primary use of this - message is to check the response and signs of the - controller before actual flight and to assist with - tuning controller parameters - - nav_roll : Current desired roll in degrees (float) - nav_pitch : Current desired pitch in degrees (float) - nav_bearing : Current desired heading in degrees (int16_t) - target_bearing : Bearing to current waypoint/target in degrees (int16_t) - wp_dist : Distance to active waypoint in meters (uint16_t) - alt_error : Current altitude error in meters (float) - aspd_error : Current airspeed error in meters/second (float) - xtrack_error : Current crosstrack error on x-y plane in meters (float) - - ''' - return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) - - def position_target_encode(self, x, y, z, yaw): - ''' - The goal position of the system. This position is the input to any - navigation or path planning algorithm and does NOT - represent the current controller setpoint. - - x : x position (float) - y : y position (float) - z : z position (float) - yaw : yaw orientation in radians, 0 = NORTH (float) - - ''' - msg = MAVLink_position_target_message(x, y, z, yaw) - msg.pack(self) - return msg - - def position_target_send(self, x, y, z, yaw): - ''' - The goal position of the system. This position is the input to any - navigation or path planning algorithm and does NOT - represent the current controller setpoint. - - x : x position (float) - y : y position (float) - z : z position (float) - yaw : yaw orientation in radians, 0 = NORTH (float) - - ''' - return self.send(self.position_target_encode(x, y, z, yaw)) - - def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - ''' - Corrects the systems state by adding an error correction term to the - position and velocity, and by rotating the attitude by - a correction angle. - - xErr : x position error (float) - yErr : y position error (float) - zErr : z position error (float) - rollErr : roll error (radians) (float) - pitchErr : pitch error (radians) (float) - yawErr : yaw error (radians) (float) - vxErr : x velocity (float) - vyErr : y velocity (float) - vzErr : z velocity (float) - - ''' - msg = MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr) - msg.pack(self) - return msg - - def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - ''' - Corrects the systems state by adding an error correction term to the - position and velocity, and by rotating the attitude by - a correction angle. - - xErr : x position error (float) - yErr : y position error (float) - zErr : z position error (float) - rollErr : roll error (radians) (float) - pitchErr : pitch error (radians) (float) - yawErr : yaw error (radians) (float) - vxErr : x velocity (float) - vyErr : y velocity (float) - vzErr : z velocity (float) - - ''' - return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)) - - def set_altitude_encode(self, target, mode): - ''' - - - target : The system setting the altitude (uint8_t) - mode : The new altitude in meters (uint32_t) - - ''' - msg = MAVLink_set_altitude_message(target, mode) - msg.pack(self) - return msg - - def set_altitude_send(self, target, mode): - ''' - - - target : The system setting the altitude (uint8_t) - mode : The new altitude in meters (uint32_t) - - ''' - return self.send(self.set_altitude_encode(target, mode)) - - def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - ''' - - - target_system : The target requested to send the message stream. (uint8_t) - target_component : The target requested to send the message stream. (uint8_t) - req_stream_id : The ID of the requested message type (uint8_t) - req_message_rate : Update rate in Hertz (uint16_t) - start_stop : 1 to start sending, 0 to stop sending. (uint8_t) - - ''' - msg = MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) - msg.pack(self) - return msg - - def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - ''' - - - target_system : The target requested to send the message stream. (uint8_t) - target_component : The target requested to send the message stream. (uint8_t) - req_stream_id : The ID of the requested message type (uint8_t) - req_message_rate : Update rate in Hertz (uint16_t) - start_stop : 1 to start sending, 0 to stop sending. (uint8_t) - - ''' - return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) - - def hil_state_encode(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - ''' - This packet is useful for high throughput applications - such as hardware in the loop simulations. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - - ''' - msg = MAVLink_hil_state_message(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) - msg.pack(self) - return msg - - def hil_state_send(self, usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - ''' - This packet is useful for high throughput applications - such as hardware in the loop simulations. - - usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - - ''' - return self.send(self.hil_state_encode(usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) - - def hil_controls_encode(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): - ''' - Hardware in the loop control outputs - - time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll_ailerons : Control output -3 .. 1 (float) - pitch_elevator : Control output -1 .. 1 (float) - yaw_rudder : Control output -1 .. 1 (float) - throttle : Throttle 0 .. 1 (float) - mode : System mode (MAV_MODE) (uint8_t) - nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) - - ''' - msg = MAVLink_hil_controls_message(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode) - msg.pack(self) - return msg - - def hil_controls_send(self, time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode): - ''' - Hardware in the loop control outputs - - time_us : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll_ailerons : Control output -3 .. 1 (float) - pitch_elevator : Control output -1 .. 1 (float) - yaw_rudder : Control output -1 .. 1 (float) - throttle : Throttle 0 .. 1 (float) - mode : System mode (MAV_MODE) (uint8_t) - nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) - - ''' - return self.send(self.hil_controls_encode(time_us, roll_ailerons, pitch_elevator, yaw_rudder, throttle, mode, nav_mode)) - - def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - ''' - - - target : The system to be controlled (uint8_t) - roll : roll (float) - pitch : pitch (float) - yaw : yaw (float) - thrust : thrust (float) - roll_manual : roll control enabled auto:0, manual:1 (uint8_t) - pitch_manual : pitch auto:0, manual:1 (uint8_t) - yaw_manual : yaw auto:0, manual:1 (uint8_t) - thrust_manual : thrust auto:0, manual:1 (uint8_t) - - ''' - msg = MAVLink_manual_control_message(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual) - msg.pack(self) - return msg - - def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - ''' - - - target : The system to be controlled (uint8_t) - roll : roll (float) - pitch : pitch (float) - yaw : yaw (float) - thrust : thrust (float) - roll_manual : roll control enabled auto:0, manual:1 (uint8_t) - pitch_manual : pitch auto:0, manual:1 (uint8_t) - yaw_manual : yaw auto:0, manual:1 (uint8_t) - thrust_manual : thrust auto:0, manual:1 (uint8_t) - - ''' - return self.send(self.manual_control_encode(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual)) - - def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - ''' - The RAW values of the RC channels sent to the MAV to override info - received from the RC radio. A value of -1 means no - change to that channel. A value of 0 means control of - that channel should be released back to the RC radio. - The standard PPM modulation is as follows: 1000 - microseconds: 0%, 2000 microseconds: 100%. Individual - receivers/transmitters might violate this - specification. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - - ''' - msg = MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) - msg.pack(self) - return msg - - def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - ''' - The RAW values of the RC channels sent to the MAV to override info - received from the RC radio. A value of -1 means no - change to that channel. A value of 0 means control of - that channel should be released back to the RC radio. - The standard PPM modulation is as follows: 1000 - microseconds: 0%, 2000 microseconds: 100%. Individual - receivers/transmitters might violate this - specification. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - - ''' - return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) - - def global_position_int_encode(self, lat, lon, alt, vx, vy, vz): - ''' - The filtered global position (e.g. fused GPS and accelerometers). The - position is in GPS-frame (right-handed, Z-up) - - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - - ''' - msg = MAVLink_global_position_int_message(lat, lon, alt, vx, vy, vz) - msg.pack(self) - return msg - - def global_position_int_send(self, lat, lon, alt, vx, vy, vz): - ''' - The filtered global position (e.g. fused GPS and accelerometers). The - position is in GPS-frame (right-handed, Z-up) - - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - - ''' - return self.send(self.global_position_int_encode(lat, lon, alt, vx, vy, vz)) - - def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - - airspeed : Current airspeed in m/s (float) - groundspeed : Current ground speed in m/s (float) - heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) - throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) - alt : Current altitude (MSL), in meters (float) - climb : Current climb rate in meters/second (float) - - ''' - msg = MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) - msg.pack(self) - return msg - - def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - - airspeed : Current airspeed in m/s (float) - groundspeed : Current ground speed in m/s (float) - heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) - throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) - alt : Current altitude (MSL), in meters (float) - climb : Current climb rate in meters/second (float) - - ''' - return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) - - def command_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): - ''' - Send a command with up to four parameters to the MAV - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - command : Command ID, as defined by MAV_CMD enum. (uint8_t) - confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) - param1 : Parameter 1, as defined by MAV_CMD enum. (float) - param2 : Parameter 2, as defined by MAV_CMD enum. (float) - param3 : Parameter 3, as defined by MAV_CMD enum. (float) - param4 : Parameter 4, as defined by MAV_CMD enum. (float) - - ''' - msg = MAVLink_command_message(target_system, target_component, command, confirmation, param1, param2, param3, param4) - msg.pack(self) - return msg - - def command_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4): - ''' - Send a command with up to four parameters to the MAV - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - command : Command ID, as defined by MAV_CMD enum. (uint8_t) - confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) - param1 : Parameter 1, as defined by MAV_CMD enum. (float) - param2 : Parameter 2, as defined by MAV_CMD enum. (float) - param3 : Parameter 3, as defined by MAV_CMD enum. (float) - param4 : Parameter 4, as defined by MAV_CMD enum. (float) - - ''' - return self.send(self.command_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4)) - - def command_ack_encode(self, command, result): - ''' - Report status of a command. Includes feedback wether the command was - executed - - command : Current airspeed in m/s (float) - result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) - - ''' - msg = MAVLink_command_ack_message(command, result) - msg.pack(self) - return msg - - def command_ack_send(self, command, result): - ''' - Report status of a command. Includes feedback wether the command was - executed - - command : Current airspeed in m/s (float) - result : 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION (float) - - ''' - return self.send(self.command_ack_encode(command, result)) - - def optical_flow_encode(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - - time : Timestamp (UNIX) (uint64_t) - sensor_id : Sensor ID (uint8_t) - flow_x : Flow in pixels in x-sensor direction (int16_t) - flow_y : Flow in pixels in y-sensor direction (int16_t) - quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) - ground_distance : Ground distance in meters (float) - - ''' - msg = MAVLink_optical_flow_message(time, sensor_id, flow_x, flow_y, quality, ground_distance) - msg.pack(self) - return msg - - def optical_flow_send(self, time, sensor_id, flow_x, flow_y, quality, ground_distance): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - - time : Timestamp (UNIX) (uint64_t) - sensor_id : Sensor ID (uint8_t) - flow_x : Flow in pixels in x-sensor direction (int16_t) - flow_y : Flow in pixels in y-sensor direction (int16_t) - quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) - ground_distance : Ground distance in meters (float) - - ''' - return self.send(self.optical_flow_encode(time, sensor_id, flow_x, flow_y, quality, ground_distance)) - - def object_detection_event_encode(self, time, object_id, type, name, quality, bearing, distance): - ''' - Object has been detected - - time : Timestamp in milliseconds since system boot (uint32_t) - object_id : Object ID (uint16_t) - type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) - name : Name of the object as defined by the detector (char) - quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) - bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) - distance : Ground distance in meters (float) - - ''' - msg = MAVLink_object_detection_event_message(time, object_id, type, name, quality, bearing, distance) - msg.pack(self) - return msg - - def object_detection_event_send(self, time, object_id, type, name, quality, bearing, distance): - ''' - Object has been detected - - time : Timestamp in milliseconds since system boot (uint32_t) - object_id : Object ID (uint16_t) - type : Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal (uint8_t) - name : Name of the object as defined by the detector (char) - quality : Detection quality / confidence. 0: bad, 255: maximum confidence (uint8_t) - bearing : Angle of the object with respect to the body frame in NED coordinates in radians. 0: front (float) - distance : Ground distance in meters (float) - - ''' - return self.send(self.object_detection_event_encode(time, object_id, type, name, quality, bearing, distance)) - - def debug_vect_encode(self, name, usec, x, y, z): - ''' - - - name : Name (char) - usec : Timestamp (uint64_t) - x : x (float) - y : y (float) - z : z (float) - - ''' - msg = MAVLink_debug_vect_message(name, usec, x, y, z) - msg.pack(self) - return msg - - def debug_vect_send(self, name, usec, x, y, z): - ''' - - - name : Name (char) - usec : Timestamp (uint64_t) - x : x (float) - y : y (float) - z : z (float) - - ''' - return self.send(self.debug_vect_encode(name, usec, x, y, z)) - - def named_value_float_encode(self, name, value): - ''' - Send a key-value pair as float. The use of this message is discouraged - for normal packets, but a quite efficient way for - testing new messages and getting experimental debug - output. - - name : Name of the debug variable (char) - value : Floating point value (float) - - ''' - msg = MAVLink_named_value_float_message(name, value) - msg.pack(self) - return msg - - def named_value_float_send(self, name, value): - ''' - Send a key-value pair as float. The use of this message is discouraged - for normal packets, but a quite efficient way for - testing new messages and getting experimental debug - output. - - name : Name of the debug variable (char) - value : Floating point value (float) - - ''' - return self.send(self.named_value_float_encode(name, value)) - - def named_value_int_encode(self, name, value): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient - way for testing new messages and getting experimental - debug output. - - name : Name of the debug variable (char) - value : Signed integer value (int32_t) - - ''' - msg = MAVLink_named_value_int_message(name, value) - msg.pack(self) - return msg - - def named_value_int_send(self, name, value): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient - way for testing new messages and getting experimental - debug output. - - name : Name of the debug variable (char) - value : Signed integer value (int32_t) - - ''' - return self.send(self.named_value_int_encode(name, value)) - - def statustext_encode(self, severity, text): - ''' - Status text message. These messages are printed in yellow in the COMM - console of QGroundControl. WARNING: They consume quite - some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages - are buffered on the MCU and sent only at a limited - rate (e.g. 10 Hz). - - severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) - text : Status text message, without null termination character (int8_t) - - ''' - msg = MAVLink_statustext_message(severity, text) - msg.pack(self) - return msg - - def statustext_send(self, severity, text): - ''' - Status text message. These messages are printed in yellow in the COMM - console of QGroundControl. WARNING: They consume quite - some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages - are buffered on the MCU and sent only at a limited - rate (e.g. 10 Hz). - - severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) - text : Status text message, without null termination character (int8_t) - - ''' - return self.send(self.statustext_encode(severity, text)) - - def debug_encode(self, ind, value): - ''' - Send a debug value. The index is used to discriminate between values. - These values show up in the plot of QGroundControl as - DEBUG N. - - ind : index of debug variable (uint8_t) - value : DEBUG value (float) - - ''' - msg = MAVLink_debug_message(ind, value) - msg.pack(self) - return msg - - def debug_send(self, ind, value): - ''' - Send a debug value. The index is used to discriminate between values. - These values show up in the plot of QGroundControl as - DEBUG N. - - ind : index of debug variable (uint8_t) - value : DEBUG value (float) - - ''' - return self.send(self.debug_encode(ind, value)) - diff --git a/mavlink/share/pyshared/pymavlink/mavlinkv10.py b/mavlink/share/pyshared/pymavlink/mavlinkv10.py deleted file mode 100644 index a87e8e904..000000000 --- a/mavlink/share/pyshared/pymavlink/mavlinkv10.py +++ /dev/null @@ -1,5394 +0,0 @@ -''' -MAVLink protocol implementation (auto-generated by mavgen.py) - -Generated from: ardupilotmega.xml,common.xml - -Note: this file has been auto-generated. DO NOT EDIT -''' - -import struct, array, mavutil, time - -WIRE_PROTOCOL_VERSION = "1.0" - -class MAVLink_header(object): - '''MAVLink message header''' - def __init__(self, msgId, mlen=0, seq=0, srcSystem=0, srcComponent=0): - self.mlen = mlen - self.seq = seq - self.srcSystem = srcSystem - self.srcComponent = srcComponent - self.msgId = msgId - - def pack(self): - return struct.pack('BBBBBB', 254, self.mlen, self.seq, - self.srcSystem, self.srcComponent, self.msgId) - -class MAVLink_message(object): - '''base MAVLink message class''' - def __init__(self, msgId, name): - self._header = MAVLink_header(msgId) - self._payload = None - self._msgbuf = None - self._crc = None - self._fieldnames = [] - self._type = name - - def get_msgbuf(self): - return self._msgbuf - - def get_header(self): - return self._header - - def get_payload(self): - return self._payload - - def get_crc(self): - return self._crc - - def get_fieldnames(self): - return self._fieldnames - - def get_type(self): - return self._type - - def get_msgId(self): - return self._header.msgId - - def get_srcSystem(self): - return self._header.srcSystem - - def get_srcComponent(self): - return self._header.srcComponent - - def get_seq(self): - return self._header.seq - - def __str__(self): - ret = '%s {' % self._type - for a in self._fieldnames: - v = getattr(self, a) - ret += '%s : %s, ' % (a, v) - ret = ret[0:-2] + '}' - return ret - - def pack(self, mav, crc_extra, payload): - self._payload = payload - self._header = MAVLink_header(self._header.msgId, len(payload), mav.seq, - mav.srcSystem, mav.srcComponent) - self._msgbuf = self._header.pack() + payload - crc = mavutil.x25crc(self._msgbuf[1:]) - if True: # using CRC extra - crc.accumulate(chr(crc_extra)) - self._crc = crc.crc - self._msgbuf += struct.pack(' MAV. Also used to return a point from MAV -> GCS - ''' - def __init__(self, target_system, target_component, idx, count, lat, lng): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_FENCE_POINT, 'FENCE_POINT') - self._fieldnames = ['target_system', 'target_component', 'idx', 'count', 'lat', 'lng'] - self.target_system = target_system - self.target_component = target_component - self.idx = idx - self.count = count - self.lat = lat - self.lng = lng - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 78, struct.pack(' - value[float]. This allows to send a parameter to any other - component (such as the GCS) without the need of previous - knowledge of possible parameter names. Thus the same GCS can - store different parameters for different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a full - documentation of QGroundControl and IMU code. - ''' - def __init__(self, target_system, target_component, param_id, param_index): - MAVLink_message.__init__(self, MAVLINK_MSG_ID_PARAM_REQUEST_READ, 'PARAM_REQUEST_READ') - self._fieldnames = ['target_system', 'target_component', 'param_id', 'param_index'] - self.target_system = target_system - self.target_component = target_component - self.param_id = param_id - self.param_index = param_index - - def pack(self, mav): - return MAVLink_message.pack(self, mav, 214, struct.pack('= 1 and self.buf[0] != 254: - magic = self.buf[0] - self.buf = self.buf[1:] - if self.robust_parsing: - m = MAVLink_bad_data(chr(magic), "Bad prefix") - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - self.expected_length = 6 - self.total_receive_errors += 1 - return m - if self.have_prefix_error: - return None - self.have_prefix_error = True - self.total_receive_errors += 1 - raise MAVError("invalid MAVLink prefix '%s'" % magic) - self.have_prefix_error = False - if len(self.buf) >= 2: - (magic, self.expected_length) = struct.unpack('BB', self.buf[0:2]) - self.expected_length += 8 - if self.expected_length >= 8 and len(self.buf) >= self.expected_length: - mbuf = self.buf[0:self.expected_length] - self.buf = self.buf[self.expected_length:] - self.expected_length = 6 - if self.robust_parsing: - try: - m = self.decode(mbuf) - self.total_packets_received += 1 - except MAVError as reason: - m = MAVLink_bad_data(mbuf, reason.message) - self.total_receive_errors += 1 - else: - m = self.decode(mbuf) - self.total_packets_received += 1 - if self.callback: - self.callback(m, *self.callback_args, **self.callback_kwargs) - return m - return None - - def parse_buffer(self, s): - '''input some data bytes, possibly returning a list of new messages''' - m = self.parse_char(s) - if m is None: - return None - ret = [m] - while True: - m = self.parse_char("") - if m is None: - return ret - ret.append(m) - return ret - - def decode(self, msgbuf): - '''decode a buffer as a MAVLink message''' - # decode the header - try: - magic, mlen, seq, srcSystem, srcComponent, msgId = struct.unpack('cBBBBB', msgbuf[:6]) - except struct.error as emsg: - raise MAVError('Unable to unpack MAVLink header: %s' % emsg) - if ord(magic) != 254: - raise MAVError("invalid MAVLink prefix '%s'" % magic) - if mlen != len(msgbuf)-8: - raise MAVError('invalid MAVLink message length. Got %u expected %u, msgId=%u' % (len(msgbuf)-8, mlen, msgId)) - - if not msgId in mavlink_map: - raise MAVError('unknown MAVLink message ID %u' % msgId) - - # decode the payload - (fmt, type, order_map, crc_extra) = mavlink_map[msgId] - - # decode the checksum - try: - crc, = struct.unpack(' MAV. - Also used to return a point from MAV -> GCS - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - count : total number of points (for sanity checking) (uint8_t) - lat : Latitude of point (float) - lng : Longitude of point (float) - - ''' - msg = MAVLink_fence_point_message(target_system, target_component, idx, count, lat, lng) - msg.pack(self) - return msg - - def fence_point_send(self, target_system, target_component, idx, count, lat, lng): - ''' - A fence point. Used to set a point when from GCS -> MAV. - Also used to return a point from MAV -> GCS - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - count : total number of points (for sanity checking) (uint8_t) - lat : Latitude of point (float) - lng : Longitude of point (float) - - ''' - return self.send(self.fence_point_encode(target_system, target_component, idx, count, lat, lng)) - - def fence_fetch_point_encode(self, target_system, target_component, idx): - ''' - Request a current fence point from MAV - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - - ''' - msg = MAVLink_fence_fetch_point_message(target_system, target_component, idx) - msg.pack(self) - return msg - - def fence_fetch_point_send(self, target_system, target_component, idx): - ''' - Request a current fence point from MAV - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - idx : point index (first point is 1, 0 is for return point) (uint8_t) - - ''' - return self.send(self.fence_fetch_point_encode(target_system, target_component, idx)) - - def fence_status_encode(self, breach_status, breach_count, breach_type, breach_time): - ''' - Status of geo-fencing. Sent in extended status stream when - fencing enabled - - breach_status : 0 if currently inside fence, 1 if outside (uint8_t) - breach_count : number of fence breaches (uint16_t) - breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) - breach_time : time of last breach in milliseconds since boot (uint32_t) - - ''' - msg = MAVLink_fence_status_message(breach_status, breach_count, breach_type, breach_time) - msg.pack(self) - return msg - - def fence_status_send(self, breach_status, breach_count, breach_type, breach_time): - ''' - Status of geo-fencing. Sent in extended status stream when - fencing enabled - - breach_status : 0 if currently inside fence, 1 if outside (uint8_t) - breach_count : number of fence breaches (uint16_t) - breach_type : last breach type (see FENCE_BREACH_* enum) (uint8_t) - breach_time : time of last breach in milliseconds since boot (uint32_t) - - ''' - return self.send(self.fence_status_encode(breach_status, breach_count, breach_type, breach_time)) - - def ahrs_encode(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): - ''' - Status of DCM attitude estimator - - omegaIx : X gyro drift estimate rad/s (float) - omegaIy : Y gyro drift estimate rad/s (float) - omegaIz : Z gyro drift estimate rad/s (float) - accel_weight : average accel_weight (float) - renorm_val : average renormalisation value (float) - error_rp : average error_roll_pitch value (float) - error_yaw : average error_yaw value (float) - - ''' - msg = MAVLink_ahrs_message(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw) - msg.pack(self) - return msg - - def ahrs_send(self, omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw): - ''' - Status of DCM attitude estimator - - omegaIx : X gyro drift estimate rad/s (float) - omegaIy : Y gyro drift estimate rad/s (float) - omegaIz : Z gyro drift estimate rad/s (float) - accel_weight : average accel_weight (float) - renorm_val : average renormalisation value (float) - error_rp : average error_roll_pitch value (float) - error_yaw : average error_yaw value (float) - - ''' - return self.send(self.ahrs_encode(omegaIx, omegaIy, omegaIz, accel_weight, renorm_val, error_rp, error_yaw)) - - def simstate_encode(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro): - ''' - Status of simulation environment, if used - - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - xacc : X acceleration m/s/s (float) - yacc : Y acceleration m/s/s (float) - zacc : Z acceleration m/s/s (float) - xgyro : Angular speed around X axis rad/s (float) - ygyro : Angular speed around Y axis rad/s (float) - zgyro : Angular speed around Z axis rad/s (float) - - ''' - msg = MAVLink_simstate_message(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro) - msg.pack(self) - return msg - - def simstate_send(self, roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro): - ''' - Status of simulation environment, if used - - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - xacc : X acceleration m/s/s (float) - yacc : Y acceleration m/s/s (float) - zacc : Z acceleration m/s/s (float) - xgyro : Angular speed around X axis rad/s (float) - ygyro : Angular speed around Y axis rad/s (float) - zgyro : Angular speed around Z axis rad/s (float) - - ''' - return self.send(self.simstate_encode(roll, pitch, yaw, xacc, yacc, zacc, xgyro, ygyro, zgyro)) - - def hwstatus_encode(self, Vcc, I2Cerr): - ''' - Status of key hardware - - Vcc : board voltage (mV) (uint16_t) - I2Cerr : I2C error count (uint8_t) - - ''' - msg = MAVLink_hwstatus_message(Vcc, I2Cerr) - msg.pack(self) - return msg - - def hwstatus_send(self, Vcc, I2Cerr): - ''' - Status of key hardware - - Vcc : board voltage (mV) (uint16_t) - I2Cerr : I2C error count (uint8_t) - - ''' - return self.send(self.hwstatus_encode(Vcc, I2Cerr)) - - def radio_encode(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): - ''' - Status generated by radio - - rssi : local signal strength (uint8_t) - remrssi : remote signal strength (uint8_t) - txbuf : how full the tx buffer is as a percentage (uint8_t) - noise : background noise level (uint8_t) - remnoise : remote background noise level (uint8_t) - rxerrors : receive errors (uint16_t) - fixed : count of error corrected packets (uint16_t) - - ''' - msg = MAVLink_radio_message(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed) - msg.pack(self) - return msg - - def radio_send(self, rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed): - ''' - Status generated by radio - - rssi : local signal strength (uint8_t) - remrssi : remote signal strength (uint8_t) - txbuf : how full the tx buffer is as a percentage (uint8_t) - noise : background noise level (uint8_t) - remnoise : remote background noise level (uint8_t) - rxerrors : receive errors (uint16_t) - fixed : count of error corrected packets (uint16_t) - - ''' - return self.send(self.radio_encode(rssi, remrssi, txbuf, noise, remnoise, rxerrors, fixed)) - - def heartbeat_encode(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3): - ''' - 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). - - type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) - autopilot : Autopilot type / class. defined in MAV_CLASS ENUM (uint8_t) - base_mode : System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h (uint8_t) - custom_mode : Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. (uint32_t) - system_status : System status flag, see MAV_STATUS ENUM (uint8_t) - mavlink_version : MAVLink version (uint8_t) - - ''' - msg = MAVLink_heartbeat_message(type, autopilot, base_mode, custom_mode, system_status, mavlink_version) - msg.pack(self) - return msg - - def heartbeat_send(self, type, autopilot, base_mode, custom_mode, system_status, mavlink_version=3): - ''' - 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). - - type : Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) (uint8_t) - autopilot : Autopilot type / class. defined in MAV_CLASS ENUM (uint8_t) - base_mode : System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h (uint8_t) - custom_mode : Navigation mode bitfield, see MAV_AUTOPILOT_CUSTOM_MODE ENUM for some examples. This field is autopilot-specific. (uint32_t) - system_status : System status flag, see MAV_STATUS ENUM (uint8_t) - mavlink_version : MAVLink version (uint8_t) - - ''' - return self.send(self.heartbeat_encode(type, autopilot, base_mode, custom_mode, system_status, mavlink_version)) - - def sys_status_encode(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4): - ''' - The general system state. If the system is following the MAVLink - standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is - either LOCKED (motors shut down and locked), MANUAL - (system under RC control), GUIDED (system with - autonomous position control, position setpoint - controlled manually) or AUTO (system guided by - path/waypoint planner). The NAV_MODE defined the - current flight state: LIFTOFF (often an open-loop - maneuver), LANDING, WAYPOINTS or VECTOR. This - represents the internal navigation state machine. The - system status shows wether the system is currently - active or not and if an emergency occured. During the - CRITICAL and EMERGENCY states the MAV is still - considered to be active, but should start emergency - procedures autonomously. After a failure occured it - should first move from active to critical to allow - manual intervention and then move to emergency after a - certain timeout. - - onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) - voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) - current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) - battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t) - drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) - errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) - errors_count1 : Autopilot-specific errors (uint16_t) - errors_count2 : Autopilot-specific errors (uint16_t) - errors_count3 : Autopilot-specific errors (uint16_t) - errors_count4 : Autopilot-specific errors (uint16_t) - - ''' - msg = MAVLink_sys_status_message(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4) - msg.pack(self) - return msg - - def sys_status_send(self, onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4): - ''' - The general system state. If the system is following the MAVLink - standard, the system state is mainly defined by three - orthogonal states/modes: The system mode, which is - either LOCKED (motors shut down and locked), MANUAL - (system under RC control), GUIDED (system with - autonomous position control, position setpoint - controlled manually) or AUTO (system guided by - path/waypoint planner). The NAV_MODE defined the - current flight state: LIFTOFF (often an open-loop - maneuver), LANDING, WAYPOINTS or VECTOR. This - represents the internal navigation state machine. The - system status shows wether the system is currently - active or not and if an emergency occured. During the - CRITICAL and EMERGENCY states the MAV is still - considered to be active, but should start emergency - procedures autonomously. After a failure occured it - should first move from active to critical to allow - manual intervention and then move to emergency after a - certain timeout. - - onboard_control_sensors_present : Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - onboard_control_sensors_enabled : Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - onboard_control_sensors_health : Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control (uint32_t) - load : Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000 (uint16_t) - voltage_battery : Battery voltage, in millivolts (1 = 1 millivolt) (uint16_t) - current_battery : Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current (int16_t) - battery_remaining : Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery (int8_t) - drop_rate_comm : Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) - errors_comm : Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV) (uint16_t) - errors_count1 : Autopilot-specific errors (uint16_t) - errors_count2 : Autopilot-specific errors (uint16_t) - errors_count3 : Autopilot-specific errors (uint16_t) - errors_count4 : Autopilot-specific errors (uint16_t) - - ''' - return self.send(self.sys_status_encode(onboard_control_sensors_present, onboard_control_sensors_enabled, onboard_control_sensors_health, load, voltage_battery, current_battery, battery_remaining, drop_rate_comm, errors_comm, errors_count1, errors_count2, errors_count3, errors_count4)) - - def system_time_encode(self, time_unix_usec, time_boot_ms): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - - time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) - time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t) - - ''' - msg = MAVLink_system_time_message(time_unix_usec, time_boot_ms) - msg.pack(self) - return msg - - def system_time_send(self, time_unix_usec, time_boot_ms): - ''' - The system time is the time of the master clock, typically the - computer clock of the main onboard computer. - - time_unix_usec : Timestamp of the master clock in microseconds since UNIX epoch. (uint64_t) - time_boot_ms : Timestamp of the component clock since boot time in milliseconds. (uint32_t) - - ''' - return self.send(self.system_time_encode(time_unix_usec, time_boot_ms)) - - def ping_encode(self, time_usec, seq, target_system, target_component): - ''' - A ping message either requesting or responding to a ping. This allows - to measure the system latencies, including serial - port, radio modem and UDP connections. - - time_usec : Unix timestamp in microseconds (uint64_t) - seq : PING sequence (uint32_t) - target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - - ''' - msg = MAVLink_ping_message(time_usec, seq, target_system, target_component) - msg.pack(self) - return msg - - def ping_send(self, time_usec, seq, target_system, target_component): - ''' - A ping message either requesting or responding to a ping. This allows - to measure the system latencies, including serial - port, radio modem and UDP connections. - - time_usec : Unix timestamp in microseconds (uint64_t) - seq : PING sequence (uint32_t) - target_system : 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - target_component : 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system (uint8_t) - - ''' - return self.send(self.ping_encode(time_usec, seq, target_system, target_component)) - - def change_operator_control_encode(self, target_system, control_request, version, passkey): - ''' - Request to control this MAV - - target_system : System the GCS requests control for (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) - passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) - - ''' - msg = MAVLink_change_operator_control_message(target_system, control_request, version, passkey) - msg.pack(self) - return msg - - def change_operator_control_send(self, target_system, control_request, version, passkey): - ''' - Request to control this MAV - - target_system : System the GCS requests control for (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - version : 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch. (uint8_t) - passkey : Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-" (char) - - ''' - return self.send(self.change_operator_control_encode(target_system, control_request, version, passkey)) - - def change_operator_control_ack_encode(self, gcs_system_id, control_request, ack): - ''' - Accept / deny control of this MAV - - gcs_system_id : ID of the GCS this message (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) - - ''' - msg = MAVLink_change_operator_control_ack_message(gcs_system_id, control_request, ack) - msg.pack(self) - return msg - - def change_operator_control_ack_send(self, gcs_system_id, control_request, ack): - ''' - Accept / deny control of this MAV - - gcs_system_id : ID of the GCS this message (uint8_t) - control_request : 0: request control of this MAV, 1: Release control of this MAV (uint8_t) - ack : 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control (uint8_t) - - ''' - return self.send(self.change_operator_control_ack_encode(gcs_system_id, control_request, ack)) - - def auth_key_encode(self, key): - ''' - Emit an encrypted signature / key identifying this system. PLEASE - NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for - true safety. - - key : key (char) - - ''' - msg = MAVLink_auth_key_message(key) - msg.pack(self) - return msg - - def auth_key_send(self, key): - ''' - Emit an encrypted signature / key identifying this system. PLEASE - NOTE: This protocol has been kept simple, so - transmitting the key requires an encrypted channel for - true safety. - - key : key (char) - - ''' - return self.send(self.auth_key_encode(key)) - - def set_mode_encode(self, target_system, base_mode, custom_mode): - ''' - Set the system mode, as defined by enum MAV_MODE. There is no target - component id as the mode is by definition for the - overall aircraft, not only for one component. - - target_system : The system setting the mode (uint8_t) - base_mode : The new base mode (uint8_t) - custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t) - - ''' - msg = MAVLink_set_mode_message(target_system, base_mode, custom_mode) - msg.pack(self) - return msg - - def set_mode_send(self, target_system, base_mode, custom_mode): - ''' - Set the system mode, as defined by enum MAV_MODE. There is no target - component id as the mode is by definition for the - overall aircraft, not only for one component. - - target_system : The system setting the mode (uint8_t) - base_mode : The new base mode (uint8_t) - custom_mode : The new autopilot-specific mode. This field can be ignored by an autopilot. (uint32_t) - - ''' - return self.send(self.set_mode_encode(target_system, base_mode, custom_mode)) - - def param_request_read_encode(self, target_system, target_component, param_id, param_index): - ''' - Request to read the onboard parameter with the param_id string id. - Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any - other component (such as the GCS) without the need of - previous knowledge of possible parameter names. Thus - the same GCS can store different parameters for - different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a - full documentation of QGroundControl and IMU code. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (char) - param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) - - ''' - msg = MAVLink_param_request_read_message(target_system, target_component, param_id, param_index) - msg.pack(self) - return msg - - def param_request_read_send(self, target_system, target_component, param_id, param_index): - ''' - Request to read the onboard parameter with the param_id string id. - Onboard parameters are stored as key[const char*] -> - value[float]. This allows to send a parameter to any - other component (such as the GCS) without the need of - previous knowledge of possible parameter names. Thus - the same GCS can store different parameters for - different autopilots. See also - http://qgroundcontrol.org/parameter_interface for a - full documentation of QGroundControl and IMU code. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (char) - param_index : Parameter index. Send -1 to use the param ID field as identifier (int16_t) - - ''' - return self.send(self.param_request_read_encode(target_system, target_component, param_id, param_index)) - - def param_request_list_encode(self, target_system, target_component): - ''' - Request all parameters of this component. After his request, all - parameters are emitted. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_param_request_list_message(target_system, target_component) - msg.pack(self) - return msg - - def param_request_list_send(self, target_system, target_component): - ''' - Request all parameters of this component. After his request, all - parameters are emitted. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.param_request_list_encode(target_system, target_component)) - - def param_value_encode(self, param_id, param_value, param_type, param_count, param_index): - ''' - Emit the value of a onboard parameter. The inclusion of param_count - and param_index in the message allows the recipient to - keep track of received parameters and allows him to - re-request missing parameters after a loss or timeout. - - param_id : Onboard parameter id (char) - param_value : Onboard parameter value (float) - param_type : Onboard parameter type: see MAV_VAR enum (uint8_t) - param_count : Total number of onboard parameters (uint16_t) - param_index : Index of this onboard parameter (uint16_t) - - ''' - msg = MAVLink_param_value_message(param_id, param_value, param_type, param_count, param_index) - msg.pack(self) - return msg - - def param_value_send(self, param_id, param_value, param_type, param_count, param_index): - ''' - Emit the value of a onboard parameter. The inclusion of param_count - and param_index in the message allows the recipient to - keep track of received parameters and allows him to - re-request missing parameters after a loss or timeout. - - param_id : Onboard parameter id (char) - param_value : Onboard parameter value (float) - param_type : Onboard parameter type: see MAV_VAR enum (uint8_t) - param_count : Total number of onboard parameters (uint16_t) - param_index : Index of this onboard parameter (uint16_t) - - ''' - return self.send(self.param_value_encode(param_id, param_value, param_type, param_count, param_index)) - - def param_set_encode(self, target_system, target_component, param_id, param_value, param_type): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to default - on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM - contents to EEPROM. IMPORTANT: The receiving component - should acknowledge the new parameter value by sending - a param_value message to all communication partners. - This will also ensure that multiple GCS all have an - up-to-date list of all parameters. If the sending GCS - did not receive a PARAM_VALUE message within its - timeout time, it should re-send the PARAM_SET message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (char) - param_value : Onboard parameter value (float) - param_type : Onboard parameter type: see MAV_VAR enum (uint8_t) - - ''' - msg = MAVLink_param_set_message(target_system, target_component, param_id, param_value, param_type) - msg.pack(self) - return msg - - def param_set_send(self, target_system, target_component, param_id, param_value, param_type): - ''' - Set a parameter value TEMPORARILY to RAM. It will be reset to default - on system reboot. Send the ACTION - MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM - contents to EEPROM. IMPORTANT: The receiving component - should acknowledge the new parameter value by sending - a param_value message to all communication partners. - This will also ensure that multiple GCS all have an - up-to-date list of all parameters. If the sending GCS - did not receive a PARAM_VALUE message within its - timeout time, it should re-send the PARAM_SET message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - param_id : Onboard parameter id (char) - param_value : Onboard parameter value (float) - param_type : Onboard parameter type: see MAV_VAR enum (uint8_t) - - ''' - return self.send(self.param_set_encode(target_system, target_component, param_id, param_value, param_type)) - - def gps_raw_int_encode(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position - estimate of the sytem, but rather a RAW sensor value. - See message GLOBAL_POSITION for the global position - estimate. Coordinate frame is right-handed, Z-axis up - (GPS frame) - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in 1E7 degrees (int32_t) - lon : Longitude in 1E7 degrees (int32_t) - alt : Altitude in 1E3 meters (millimeters) above MSL (int32_t) - eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) - epv : GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) - vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) - cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) - satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) - - ''' - msg = MAVLink_gps_raw_int_message(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible) - msg.pack(self) - return msg - - def gps_raw_int_send(self, time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible): - ''' - The global position, as returned by the Global Positioning System - (GPS). This is NOT the global position - estimate of the sytem, but rather a RAW sensor value. - See message GLOBAL_POSITION for the global position - estimate. Coordinate frame is right-handed, Z-axis up - (GPS frame) - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - fix_type : 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix. (uint8_t) - lat : Latitude in 1E7 degrees (int32_t) - lon : Longitude in 1E7 degrees (int32_t) - alt : Altitude in 1E3 meters (millimeters) above MSL (int32_t) - eph : GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) - epv : GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535 (uint16_t) - vel : GPS ground speed (m/s * 100). If unknown, set to: 65535 (uint16_t) - cog : Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) - satellites_visible : Number of satellites visible. If unknown, set to 255 (uint8_t) - - ''' - return self.send(self.gps_raw_int_encode(time_usec, fix_type, lat, lon, alt, eph, epv, vel, cog, satellites_visible)) - - def gps_status_encode(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - ''' - The positioning status, as reported by GPS. This message is intended - to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION - for the global position estimate. This message can - contain information for up to 20 satellites. - - satellites_visible : Number of satellites visible (uint8_t) - satellite_prn : Global satellite ID (uint8_t) - satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) - satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) - satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) - satellite_snr : Signal to noise ratio of satellite (uint8_t) - - ''' - msg = MAVLink_gps_status_message(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr) - msg.pack(self) - return msg - - def gps_status_send(self, satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr): - ''' - The positioning status, as reported by GPS. This message is intended - to display status information about each satellite - visible to the receiver. See message GLOBAL_POSITION - for the global position estimate. This message can - contain information for up to 20 satellites. - - satellites_visible : Number of satellites visible (uint8_t) - satellite_prn : Global satellite ID (uint8_t) - satellite_used : 0: Satellite not used, 1: used for localization (uint8_t) - satellite_elevation : Elevation (0: right on top of receiver, 90: on the horizon) of satellite (uint8_t) - satellite_azimuth : Direction of satellite, 0: 0 deg, 255: 360 deg. (uint8_t) - satellite_snr : Signal to noise ratio of satellite (uint8_t) - - ''' - return self.send(self.gps_status_encode(satellites_visible, satellite_prn, satellite_used, satellite_elevation, satellite_azimuth, satellite_snr)) - - def scaled_imu_encode(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should contain the scaled values to the described - units - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - xgyro : Angular speed around X axis (millirad /sec) (int16_t) - ygyro : Angular speed around Y axis (millirad /sec) (int16_t) - zgyro : Angular speed around Z axis (millirad /sec) (int16_t) - xmag : X Magnetic field (milli tesla) (int16_t) - ymag : Y Magnetic field (milli tesla) (int16_t) - zmag : Z Magnetic field (milli tesla) (int16_t) - - ''' - msg = MAVLink_scaled_imu_message(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) - msg.pack(self) - return msg - - def scaled_imu_send(self, time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should contain the scaled values to the described - units - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - xgyro : Angular speed around X axis (millirad /sec) (int16_t) - ygyro : Angular speed around Y axis (millirad /sec) (int16_t) - zgyro : Angular speed around Z axis (millirad /sec) (int16_t) - xmag : X Magnetic field (milli tesla) (int16_t) - ymag : Y Magnetic field (milli tesla) (int16_t) - zmag : Z Magnetic field (milli tesla) (int16_t) - - ''' - return self.send(self.scaled_imu_encode(time_boot_ms, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) - - def raw_imu_encode(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should always contain the true raw values without any - scaling to allow data capture and system debugging. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (raw) (int16_t) - yacc : Y acceleration (raw) (int16_t) - zacc : Z acceleration (raw) (int16_t) - xgyro : Angular speed around X axis (raw) (int16_t) - ygyro : Angular speed around Y axis (raw) (int16_t) - zgyro : Angular speed around Z axis (raw) (int16_t) - xmag : X Magnetic field (raw) (int16_t) - ymag : Y Magnetic field (raw) (int16_t) - zmag : Z Magnetic field (raw) (int16_t) - - ''' - msg = MAVLink_raw_imu_message(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag) - msg.pack(self) - return msg - - def raw_imu_send(self, time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag): - ''' - The RAW IMU readings for the usual 9DOF sensor setup. This message - should always contain the true raw values without any - scaling to allow data capture and system debugging. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - xacc : X acceleration (raw) (int16_t) - yacc : Y acceleration (raw) (int16_t) - zacc : Z acceleration (raw) (int16_t) - xgyro : Angular speed around X axis (raw) (int16_t) - ygyro : Angular speed around Y axis (raw) (int16_t) - zgyro : Angular speed around Z axis (raw) (int16_t) - xmag : X Magnetic field (raw) (int16_t) - ymag : Y Magnetic field (raw) (int16_t) - zmag : Z Magnetic field (raw) (int16_t) - - ''' - return self.send(self.raw_imu_encode(time_usec, xacc, yacc, zacc, xgyro, ygyro, zgyro, xmag, ymag, zmag)) - - def raw_pressure_encode(self, time_usec, press_abs, press_diff1, press_diff2, temperature): - ''' - The RAW pressure readings for the typical setup of one absolute - pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (raw) (int16_t) - press_diff1 : Differential pressure 1 (raw) (int16_t) - press_diff2 : Differential pressure 2 (raw) (int16_t) - temperature : Raw Temperature measurement (raw) (int16_t) - - ''' - msg = MAVLink_raw_pressure_message(time_usec, press_abs, press_diff1, press_diff2, temperature) - msg.pack(self) - return msg - - def raw_pressure_send(self, time_usec, press_abs, press_diff1, press_diff2, temperature): - ''' - The RAW pressure readings for the typical setup of one absolute - pressure and one differential pressure sensor. The - sensor values should be the raw, UNSCALED ADC values. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - press_abs : Absolute pressure (raw) (int16_t) - press_diff1 : Differential pressure 1 (raw) (int16_t) - press_diff2 : Differential pressure 2 (raw) (int16_t) - temperature : Raw Temperature measurement (raw) (int16_t) - - ''' - return self.send(self.raw_pressure_encode(time_usec, press_abs, press_diff1, press_diff2, temperature)) - - def scaled_pressure_encode(self, time_boot_ms, press_abs, press_diff, temperature): - ''' - The pressure readings for the typical setup of one absolute and - differential pressure sensor. The units are as - specified in each field. - - time_boot_ms : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint32_t) - press_abs : Absolute pressure (hectopascal) (float) - press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) - - ''' - msg = MAVLink_scaled_pressure_message(time_boot_ms, press_abs, press_diff, temperature) - msg.pack(self) - return msg - - def scaled_pressure_send(self, time_boot_ms, press_abs, press_diff, temperature): - ''' - The pressure readings for the typical setup of one absolute and - differential pressure sensor. The units are as - specified in each field. - - time_boot_ms : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint32_t) - press_abs : Absolute pressure (hectopascal) (float) - press_diff : Differential pressure 1 (hectopascal) (float) - temperature : Temperature measurement (0.01 degrees celsius) (int16_t) - - ''' - return self.send(self.scaled_pressure_encode(time_boot_ms, press_abs, press_diff, temperature)) - - def attitude_encode(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right). - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - msg = MAVLink_attitude_message(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed) - msg.pack(self) - return msg - - def attitude_send(self, time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right). - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - return self.send(self.attitude_encode(time_boot_ms, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed)) - - def attitude_quaternion_encode(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right), expressed as quaternion. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - q1 : Quaternion component 1 (float) - q2 : Quaternion component 2 (float) - q3 : Quaternion component 3 (float) - q4 : Quaternion component 4 (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - msg = MAVLink_attitude_quaternion_message(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed) - msg.pack(self) - return msg - - def attitude_quaternion_send(self, time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed): - ''' - The attitude in the aeronautical frame (right-handed, Z-down, X-front, - Y-right), expressed as quaternion. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - q1 : Quaternion component 1 (float) - q2 : Quaternion component 2 (float) - q3 : Quaternion component 3 (float) - q4 : Quaternion component 4 (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - - ''' - return self.send(self.attitude_quaternion_encode(time_boot_ms, q1, q2, q3, q4, rollspeed, pitchspeed, yawspeed)) - - def local_position_ned_encode(self, time_boot_ms, x, y, z, vx, vy, vz): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, - Z-axis down (aeronautical frame, NED / north-east-down - convention) - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - x : X Position (float) - y : Y Position (float) - z : Z Position (float) - vx : X Speed (float) - vy : Y Speed (float) - vz : Z Speed (float) - - ''' - msg = MAVLink_local_position_ned_message(time_boot_ms, x, y, z, vx, vy, vz) - msg.pack(self) - return msg - - def local_position_ned_send(self, time_boot_ms, x, y, z, vx, vy, vz): - ''' - The filtered local position (e.g. fused computer vision and - accelerometers). Coordinate frame is right-handed, - Z-axis down (aeronautical frame, NED / north-east-down - convention) - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - x : X Position (float) - y : Y Position (float) - z : Z Position (float) - vx : X Speed (float) - vy : Y Speed (float) - vz : Z Speed (float) - - ''' - return self.send(self.local_position_ned_encode(time_boot_ms, x, y, z, vx, vy, vz)) - - def global_position_int_encode(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): - ''' - The filtered global position (e.g. fused GPS and accelerometers). The - position is in GPS-frame (right-handed, Z-up). It - is designed as scaled integer message since the - resolution of float is not sufficient. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) - relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) - - ''' - msg = MAVLink_global_position_int_message(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg) - msg.pack(self) - return msg - - def global_position_int_send(self, time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg): - ''' - The filtered global position (e.g. fused GPS and accelerometers). The - position is in GPS-frame (right-handed, Z-up). It - is designed as scaled integer message since the - resolution of float is not sufficient. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters), above MSL (int32_t) - relative_alt : Altitude above ground in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - hdg : Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535 (uint16_t) - - ''' - return self.send(self.global_position_int_encode(time_boot_ms, lat, lon, alt, relative_alt, vx, vy, vz, hdg)) - - def rc_channels_scaled_encode(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - ''' - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, - (100%) 10000 - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_rc_channels_scaled_message(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi) - msg.pack(self) - return msg - - def rc_channels_scaled_send(self, time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi): - ''' - The scaled values of the RC channels received. (-100%) -10000, (0%) 0, - (100%) 10000 - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - chan1_scaled : RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan2_scaled : RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan3_scaled : RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan4_scaled : RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan5_scaled : RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan6_scaled : RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan7_scaled : RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - chan8_scaled : RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000 (int16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.rc_channels_scaled_encode(time_boot_ms, port, chan1_scaled, chan2_scaled, chan3_scaled, chan4_scaled, chan5_scaled, chan6_scaled, chan7_scaled, chan8_scaled, rssi)) - - def rc_channels_raw_encode(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters - might violate this specification. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_rc_channels_raw_message(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi) - msg.pack(self) - return msg - - def rc_channels_raw_send(self, time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi): - ''' - The RAW values of the RC channels received. The standard PPM - modulation is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. Individual receivers/transmitters - might violate this specification. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.rc_channels_raw_encode(time_boot_ms, port, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, rssi)) - - def servo_output_raw_encode(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - ''' - The RAW values of the servo outputs (for RC input from the remote, use - the RC_CHANNELS messages). The standard PPM modulation - is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - - time_usec : Timestamp (since UNIX epoch or microseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - servo1_raw : Servo output 1 value, in microseconds (uint16_t) - servo2_raw : Servo output 2 value, in microseconds (uint16_t) - servo3_raw : Servo output 3 value, in microseconds (uint16_t) - servo4_raw : Servo output 4 value, in microseconds (uint16_t) - servo5_raw : Servo output 5 value, in microseconds (uint16_t) - servo6_raw : Servo output 6 value, in microseconds (uint16_t) - servo7_raw : Servo output 7 value, in microseconds (uint16_t) - servo8_raw : Servo output 8 value, in microseconds (uint16_t) - - ''' - msg = MAVLink_servo_output_raw_message(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw) - msg.pack(self) - return msg - - def servo_output_raw_send(self, time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw): - ''' - The RAW values of the servo outputs (for RC input from the remote, use - the RC_CHANNELS messages). The standard PPM modulation - is as follows: 1000 microseconds: 0%, 2000 - microseconds: 100%. - - time_usec : Timestamp (since UNIX epoch or microseconds since system boot) (uint32_t) - port : Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos. (uint8_t) - servo1_raw : Servo output 1 value, in microseconds (uint16_t) - servo2_raw : Servo output 2 value, in microseconds (uint16_t) - servo3_raw : Servo output 3 value, in microseconds (uint16_t) - servo4_raw : Servo output 4 value, in microseconds (uint16_t) - servo5_raw : Servo output 5 value, in microseconds (uint16_t) - servo6_raw : Servo output 6 value, in microseconds (uint16_t) - servo7_raw : Servo output 7 value, in microseconds (uint16_t) - servo8_raw : Servo output 8 value, in microseconds (uint16_t) - - ''' - return self.send(self.servo_output_raw_encode(time_usec, port, servo1_raw, servo2_raw, servo3_raw, servo4_raw, servo5_raw, servo6_raw, servo7_raw, servo8_raw)) - - def mission_request_partial_list_encode(self, target_system, target_component, start_index, end_index): - ''' - Request the overall list of MISSIONs from the system/component. - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - start_index : Start index, 0 by default (int16_t) - end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) - - ''' - msg = MAVLink_mission_request_partial_list_message(target_system, target_component, start_index, end_index) - msg.pack(self) - return msg - - def mission_request_partial_list_send(self, target_system, target_component, start_index, end_index): - ''' - Request the overall list of MISSIONs from the system/component. - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - start_index : Start index, 0 by default (int16_t) - end_index : End index, -1 by default (-1: send list to end). Else a valid index of the list (int16_t) - - ''' - return self.send(self.mission_request_partial_list_encode(target_system, target_component, start_index, end_index)) - - def mission_write_partial_list_encode(self, target_system, target_component, start_index, end_index): - ''' - This message is sent to the MAV to write a partial list. If start - index == end index, only one item will be transmitted - / updated. If the start index is NOT 0 and above the - current list size, this request should be REJECTED! - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) - end_index : End index, equal or greater than start index. (int16_t) - - ''' - msg = MAVLink_mission_write_partial_list_message(target_system, target_component, start_index, end_index) - msg.pack(self) - return msg - - def mission_write_partial_list_send(self, target_system, target_component, start_index, end_index): - ''' - This message is sent to the MAV to write a partial list. If start - index == end index, only one item will be transmitted - / updated. If the start index is NOT 0 and above the - current list size, this request should be REJECTED! - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - start_index : Start index, 0 by default and smaller / equal to the largest index of the current onboard list. (int16_t) - end_index : End index, equal or greater than start index. (int16_t) - - ''' - return self.send(self.mission_write_partial_list_encode(target_system, target_component, start_index, end_index)) - - def mission_item_encode(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - ''' - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission - item on the system. The mission item can be either in - x, y, z meters (type: LOCAL) or x:lat, y:lon, - z:altitude. Local frame is Z-down, right handed (NED), - global frame is Z-up, right handed (ENU). - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) - command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) - current : false:0, true:1 (uint8_t) - autocontinue : autocontinue to next wp (uint8_t) - param1 : PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters (float) - param2 : PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) - param3 : PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) - param4 : PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH (float) - x : PARAM5 / local: x position, global: latitude (float) - y : PARAM6 / y position: global: longitude (float) - z : PARAM7 / z position: global: altitude (float) - - ''' - msg = MAVLink_mission_item_message(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z) - msg.pack(self) - return msg - - def mission_item_send(self, target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z): - ''' - Message encoding a mission item. This message is emitted to announce - the presence of a mission item and to set a mission - item on the system. The mission item can be either in - x, y, z meters (type: LOCAL) or x:lat, y:lon, - z:altitude. Local frame is Z-down, right handed (NED), - global frame is Z-up, right handed (ENU). - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - frame : The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h (uint8_t) - command : The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs (uint16_t) - current : false:0, true:1 (uint8_t) - autocontinue : autocontinue to next wp (uint8_t) - param1 : PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters (float) - param2 : PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds (float) - param3 : PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise. (float) - param4 : PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH (float) - x : PARAM5 / local: x position, global: latitude (float) - y : PARAM6 / y position: global: longitude (float) - z : PARAM7 / z position: global: altitude (float) - - ''' - return self.send(self.mission_item_encode(target_system, target_component, seq, frame, command, current, autocontinue, param1, param2, param3, param4, x, y, z)) - - def mission_request_encode(self, target_system, target_component, seq): - ''' - Request the information of the mission item with the sequence number - seq. The response of the system to this message should - be a MISSION_ITEM message. - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_mission_request_message(target_system, target_component, seq) - msg.pack(self) - return msg - - def mission_request_send(self, target_system, target_component, seq): - ''' - Request the information of the mission item with the sequence number - seq. The response of the system to this message should - be a MISSION_ITEM message. - http://qgroundcontrol.org/mavlink/waypoint_protocol - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - return self.send(self.mission_request_encode(target_system, target_component, seq)) - - def mission_set_current_encode(self, target_system, target_component, seq): - ''' - Set the mission item with sequence number seq as current item. This - means that the MAV will continue to this mission item - on the shortest path (not following the mission items - in-between). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_mission_set_current_message(target_system, target_component, seq) - msg.pack(self) - return msg - - def mission_set_current_send(self, target_system, target_component, seq): - ''' - Set the mission item with sequence number seq as current item. This - means that the MAV will continue to this mission item - on the shortest path (not following the mission items - in-between). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - seq : Sequence (uint16_t) - - ''' - return self.send(self.mission_set_current_encode(target_system, target_component, seq)) - - def mission_current_encode(self, seq): - ''' - Message that announces the sequence number of the current active - mission item. The MAV will fly towards this mission - item. - - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_mission_current_message(seq) - msg.pack(self) - return msg - - def mission_current_send(self, seq): - ''' - Message that announces the sequence number of the current active - mission item. The MAV will fly towards this mission - item. - - seq : Sequence (uint16_t) - - ''' - return self.send(self.mission_current_encode(seq)) - - def mission_request_list_encode(self, target_system, target_component): - ''' - Request the overall list of mission items from the system/component. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_mission_request_list_message(target_system, target_component) - msg.pack(self) - return msg - - def mission_request_list_send(self, target_system, target_component): - ''' - Request the overall list of mission items from the system/component. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.mission_request_list_encode(target_system, target_component)) - - def mission_count_encode(self, target_system, target_component, count): - ''' - This message is emitted as response to MISSION_REQUEST_LIST by the MAV - and to initiate a write transaction. The GCS can then - request the individual mission item based on the - knowledge of the total number of MISSIONs. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - count : Number of mission items in the sequence (uint16_t) - - ''' - msg = MAVLink_mission_count_message(target_system, target_component, count) - msg.pack(self) - return msg - - def mission_count_send(self, target_system, target_component, count): - ''' - This message is emitted as response to MISSION_REQUEST_LIST by the MAV - and to initiate a write transaction. The GCS can then - request the individual mission item based on the - knowledge of the total number of MISSIONs. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - count : Number of mission items in the sequence (uint16_t) - - ''' - return self.send(self.mission_count_encode(target_system, target_component, count)) - - def mission_clear_all_encode(self, target_system, target_component): - ''' - Delete all mission items at once. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - msg = MAVLink_mission_clear_all_message(target_system, target_component) - msg.pack(self) - return msg - - def mission_clear_all_send(self, target_system, target_component): - ''' - Delete all mission items at once. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - - ''' - return self.send(self.mission_clear_all_encode(target_system, target_component)) - - def mission_item_reached_encode(self, seq): - ''' - A certain mission item has been reached. The system will either hold - this position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next - MISSION. - - seq : Sequence (uint16_t) - - ''' - msg = MAVLink_mission_item_reached_message(seq) - msg.pack(self) - return msg - - def mission_item_reached_send(self, seq): - ''' - A certain mission item has been reached. The system will either hold - this position (or circle on the orbit) or (if the - autocontinue on the WP was set) continue to the next - MISSION. - - seq : Sequence (uint16_t) - - ''' - return self.send(self.mission_item_reached_encode(seq)) - - def mission_ack_encode(self, target_system, target_component, type): - ''' - Ack message during MISSION handling. The type field states if this - message is a positive ack (type=0) or if an error - happened (type=non-zero). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - type : See MAV_MISSION_RESULT enum (uint8_t) - - ''' - msg = MAVLink_mission_ack_message(target_system, target_component, type) - msg.pack(self) - return msg - - def mission_ack_send(self, target_system, target_component, type): - ''' - Ack message during MISSION handling. The type field states if this - message is a positive ack (type=0) or if an error - happened (type=non-zero). - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - type : See MAV_MISSION_RESULT enum (uint8_t) - - ''' - return self.send(self.mission_ack_encode(target_system, target_component, type)) - - def set_gps_global_origin_encode(self, target_system, latitude, longitude, altitude): - ''' - As local MISSIONs exist, the global MISSION reference allows to - transform between the local coordinate frame and the - global (GPS) coordinate frame. This can be necessary - when e.g. in- and outdoor settings are connected and - the MAV should move from in- to outdoor. - - target_system : System ID (uint8_t) - latitude : global position * 1E7 (int32_t) - longitude : global position * 1E7 (int32_t) - altitude : global position * 1000 (int32_t) - - ''' - msg = MAVLink_set_gps_global_origin_message(target_system, latitude, longitude, altitude) - msg.pack(self) - return msg - - def set_gps_global_origin_send(self, target_system, latitude, longitude, altitude): - ''' - As local MISSIONs exist, the global MISSION reference allows to - transform between the local coordinate frame and the - global (GPS) coordinate frame. This can be necessary - when e.g. in- and outdoor settings are connected and - the MAV should move from in- to outdoor. - - target_system : System ID (uint8_t) - latitude : global position * 1E7 (int32_t) - longitude : global position * 1E7 (int32_t) - altitude : global position * 1000 (int32_t) - - ''' - return self.send(self.set_gps_global_origin_encode(target_system, latitude, longitude, altitude)) - - def gps_global_origin_encode(self, latitude, longitude, altitude): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - - latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) - longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) - altitude : Altitude(WGS84), expressed as * 1000 (int32_t) - - ''' - msg = MAVLink_gps_global_origin_message(latitude, longitude, altitude) - msg.pack(self) - return msg - - def gps_global_origin_send(self, latitude, longitude, altitude): - ''' - Once the MAV sets a new GPS-Local correspondence, this message - announces the origin (0,0,0) position - - latitude : Latitude (WGS84), expressed as * 1E7 (int32_t) - longitude : Longitude (WGS84), expressed as * 1E7 (int32_t) - altitude : Altitude(WGS84), expressed as * 1000 (int32_t) - - ''' - return self.send(self.gps_global_origin_encode(latitude, longitude, altitude)) - - def set_local_position_setpoint_encode(self, target_system, target_component, coordinate_frame, x, y, z, yaw): - ''' - Set the setpoint for a local position controller. This is the position - in local coordinates the MAV should fly to. This - message is sent by the path/MISSION planner to the - onboard position controller. As some MAVs have a - degree of freedom in yaw (e.g. all - helicopters/quadrotors), the desired yaw angle is part - of the message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - msg = MAVLink_set_local_position_setpoint_message(target_system, target_component, coordinate_frame, x, y, z, yaw) - msg.pack(self) - return msg - - def set_local_position_setpoint_send(self, target_system, target_component, coordinate_frame, x, y, z, yaw): - ''' - Set the setpoint for a local position controller. This is the position - in local coordinates the MAV should fly to. This - message is sent by the path/MISSION planner to the - onboard position controller. As some MAVs have a - degree of freedom in yaw (e.g. all - helicopters/quadrotors), the desired yaw angle is part - of the message. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - return self.send(self.set_local_position_setpoint_encode(target_system, target_component, coordinate_frame, x, y, z, yaw)) - - def local_position_setpoint_encode(self, coordinate_frame, x, y, z, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - msg = MAVLink_local_position_setpoint_message(coordinate_frame, x, y, z, yaw) - msg.pack(self) - return msg - - def local_position_setpoint_send(self, coordinate_frame, x, y, z, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU (uint8_t) - x : x position (float) - y : y position (float) - z : z position (float) - yaw : Desired yaw angle (float) - - ''' - return self.send(self.local_position_setpoint_encode(coordinate_frame, x, y, z, yaw)) - - def global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) - latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) - longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) - altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) - yaw : Desired yaw angle in degrees * 100 (int16_t) - - ''' - msg = MAVLink_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw) - msg.pack(self) - return msg - - def global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw): - ''' - Transmit the current local setpoint of the controller to other MAVs - (collision avoidance) and to the GCS. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) - latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) - longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) - altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) - yaw : Desired yaw angle in degrees * 100 (int16_t) - - ''' - return self.send(self.global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, yaw)) - - def set_global_position_setpoint_int_encode(self, coordinate_frame, latitude, longitude, altitude, yaw): - ''' - Set the current global position setpoint. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) - latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) - longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) - altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) - yaw : Desired yaw angle in degrees * 100 (int16_t) - - ''' - msg = MAVLink_set_global_position_setpoint_int_message(coordinate_frame, latitude, longitude, altitude, yaw) - msg.pack(self) - return msg - - def set_global_position_setpoint_int_send(self, coordinate_frame, latitude, longitude, altitude, yaw): - ''' - Set the current global position setpoint. - - coordinate_frame : Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT (uint8_t) - latitude : WGS84 Latitude position in degrees * 1E7 (int32_t) - longitude : WGS84 Longitude position in degrees * 1E7 (int32_t) - altitude : WGS84 Altitude in meters * 1000 (positive for up) (int32_t) - yaw : Desired yaw angle in degrees * 100 (int16_t) - - ''' - return self.send(self.set_global_position_setpoint_int_encode(coordinate_frame, latitude, longitude, altitude, yaw)) - - def safety_set_allowed_area_encode(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Set a safety zone (volume), which is defined by two corners of a cube. - This message can be used to tell the MAV which - setpoints/MISSIONs to accept and which to reject. - Safety areas are often enforced by national or - competition regulations. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - msg = MAVLink_safety_set_allowed_area_message(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z) - msg.pack(self) - return msg - - def safety_set_allowed_area_send(self, target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Set a safety zone (volume), which is defined by two corners of a cube. - This message can be used to tell the MAV which - setpoints/MISSIONs to accept and which to reject. - Safety areas are often enforced by national or - competition regulations. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - return self.send(self.safety_set_allowed_area_encode(target_system, target_component, frame, p1x, p1y, p1z, p2x, p2y, p2z)) - - def safety_allowed_area_encode(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Read out the safety zone the MAV currently assumes. - - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - msg = MAVLink_safety_allowed_area_message(frame, p1x, p1y, p1z, p2x, p2y, p2z) - msg.pack(self) - return msg - - def safety_allowed_area_send(self, frame, p1x, p1y, p1z, p2x, p2y, p2z): - ''' - Read out the safety zone the MAV currently assumes. - - frame : Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down. (uint8_t) - p1x : x position 1 / Latitude 1 (float) - p1y : y position 1 / Longitude 1 (float) - p1z : z position 1 / Altitude 1 (float) - p2x : x position 2 / Latitude 2 (float) - p2y : y position 2 / Longitude 2 (float) - p2z : z position 2 / Altitude 2 (float) - - ''' - return self.send(self.safety_allowed_area_encode(frame, p1x, p1y, p1z, p2x, p2y, p2z)) - - def set_roll_pitch_yaw_thrust_encode(self, target_system, target_component, roll, pitch, yaw, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_set_roll_pitch_yaw_thrust_message(target_system, target_component, roll, pitch, yaw, thrust) - msg.pack(self) - return msg - - def set_roll_pitch_yaw_thrust_send(self, target_system, target_component, roll, pitch, yaw, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.set_roll_pitch_yaw_thrust_encode(target_system, target_component, roll, pitch, yaw, thrust)) - - def set_roll_pitch_yaw_speed_thrust_encode(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_set_roll_pitch_yaw_speed_thrust_message(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust) - msg.pack(self) - return msg - - def set_roll_pitch_yaw_speed_thrust_send(self, target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Set roll, pitch and yaw. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.set_roll_pitch_yaw_speed_thrust_encode(target_system, target_component, roll_speed, pitch_speed, yaw_speed, thrust)) - - def roll_pitch_yaw_thrust_setpoint_encode(self, time_boot_ms, roll, pitch, yaw, thrust): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - - time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_roll_pitch_yaw_thrust_setpoint_message(time_boot_ms, roll, pitch, yaw, thrust) - msg.pack(self) - return msg - - def roll_pitch_yaw_thrust_setpoint_send(self, time_boot_ms, roll, pitch, yaw, thrust): - ''' - Setpoint in roll, pitch, yaw currently active on the system. - - time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) - roll : Desired roll angle in radians (float) - pitch : Desired pitch angle in radians (float) - yaw : Desired yaw angle in radians (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.roll_pitch_yaw_thrust_setpoint_encode(time_boot_ms, roll, pitch, yaw, thrust)) - - def roll_pitch_yaw_speed_thrust_setpoint_encode(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active on the - system. - - time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - msg = MAVLink_roll_pitch_yaw_speed_thrust_setpoint_message(time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust) - msg.pack(self) - return msg - - def roll_pitch_yaw_speed_thrust_setpoint_send(self, time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust): - ''' - Setpoint in rollspeed, pitchspeed, yawspeed currently active on the - system. - - time_boot_ms : Timestamp in milliseconds since system boot (uint32_t) - roll_speed : Desired roll angular speed in rad/s (float) - pitch_speed : Desired pitch angular speed in rad/s (float) - yaw_speed : Desired yaw angular speed in rad/s (float) - thrust : Collective thrust, normalized to 0 .. 1 (float) - - ''' - return self.send(self.roll_pitch_yaw_speed_thrust_setpoint_encode(time_boot_ms, roll_speed, pitch_speed, yaw_speed, thrust)) - - def nav_controller_output_encode(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - ''' - Outputs of the APM navigation controller. The primary use of this - message is to check the response and signs - of the controller before actual flight and to assist - with tuning controller parameters - - nav_roll : Current desired roll in degrees (float) - nav_pitch : Current desired pitch in degrees (float) - nav_bearing : Current desired heading in degrees (int16_t) - target_bearing : Bearing to current MISSION/target in degrees (int16_t) - wp_dist : Distance to active MISSION in meters (uint16_t) - alt_error : Current altitude error in meters (float) - aspd_error : Current airspeed error in meters/second (float) - xtrack_error : Current crosstrack error on x-y plane in meters (float) - - ''' - msg = MAVLink_nav_controller_output_message(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error) - msg.pack(self) - return msg - - def nav_controller_output_send(self, nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error): - ''' - Outputs of the APM navigation controller. The primary use of this - message is to check the response and signs - of the controller before actual flight and to assist - with tuning controller parameters - - nav_roll : Current desired roll in degrees (float) - nav_pitch : Current desired pitch in degrees (float) - nav_bearing : Current desired heading in degrees (int16_t) - target_bearing : Bearing to current MISSION/target in degrees (int16_t) - wp_dist : Distance to active MISSION in meters (uint16_t) - alt_error : Current altitude error in meters (float) - aspd_error : Current airspeed error in meters/second (float) - xtrack_error : Current crosstrack error on x-y plane in meters (float) - - ''' - return self.send(self.nav_controller_output_encode(nav_roll, nav_pitch, nav_bearing, target_bearing, wp_dist, alt_error, aspd_error, xtrack_error)) - - def state_correction_encode(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - ''' - Corrects the systems state by adding an error correction term to the - position and velocity, and by rotating the attitude by - a correction angle. - - xErr : x position error (float) - yErr : y position error (float) - zErr : z position error (float) - rollErr : roll error (radians) (float) - pitchErr : pitch error (radians) (float) - yawErr : yaw error (radians) (float) - vxErr : x velocity (float) - vyErr : y velocity (float) - vzErr : z velocity (float) - - ''' - msg = MAVLink_state_correction_message(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr) - msg.pack(self) - return msg - - def state_correction_send(self, xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr): - ''' - Corrects the systems state by adding an error correction term to the - position and velocity, and by rotating the attitude by - a correction angle. - - xErr : x position error (float) - yErr : y position error (float) - zErr : z position error (float) - rollErr : roll error (radians) (float) - pitchErr : pitch error (radians) (float) - yawErr : yaw error (radians) (float) - vxErr : x velocity (float) - vyErr : y velocity (float) - vzErr : z velocity (float) - - ''' - return self.send(self.state_correction_encode(xErr, yErr, zErr, rollErr, pitchErr, yawErr, vxErr, vyErr, vzErr)) - - def request_data_stream_encode(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - ''' - - - target_system : The target requested to send the message stream. (uint8_t) - target_component : The target requested to send the message stream. (uint8_t) - req_stream_id : The ID of the requested data stream (uint8_t) - req_message_rate : The requested interval between two messages of this type (uint16_t) - start_stop : 1 to start sending, 0 to stop sending. (uint8_t) - - ''' - msg = MAVLink_request_data_stream_message(target_system, target_component, req_stream_id, req_message_rate, start_stop) - msg.pack(self) - return msg - - def request_data_stream_send(self, target_system, target_component, req_stream_id, req_message_rate, start_stop): - ''' - - - target_system : The target requested to send the message stream. (uint8_t) - target_component : The target requested to send the message stream. (uint8_t) - req_stream_id : The ID of the requested data stream (uint8_t) - req_message_rate : The requested interval between two messages of this type (uint16_t) - start_stop : 1 to start sending, 0 to stop sending. (uint8_t) - - ''' - return self.send(self.request_data_stream_encode(target_system, target_component, req_stream_id, req_message_rate, start_stop)) - - def data_stream_encode(self, stream_id, message_rate, on_off): - ''' - - - stream_id : The ID of the requested data stream (uint8_t) - message_rate : The requested interval between two messages of this type (uint16_t) - on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) - - ''' - msg = MAVLink_data_stream_message(stream_id, message_rate, on_off) - msg.pack(self) - return msg - - def data_stream_send(self, stream_id, message_rate, on_off): - ''' - - - stream_id : The ID of the requested data stream (uint8_t) - message_rate : The requested interval between two messages of this type (uint16_t) - on_off : 1 stream is enabled, 0 stream is stopped. (uint8_t) - - ''' - return self.send(self.data_stream_encode(stream_id, message_rate, on_off)) - - def manual_control_encode(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - ''' - - - target : The system to be controlled (uint8_t) - roll : roll (float) - pitch : pitch (float) - yaw : yaw (float) - thrust : thrust (float) - roll_manual : roll control enabled auto:0, manual:1 (uint8_t) - pitch_manual : pitch auto:0, manual:1 (uint8_t) - yaw_manual : yaw auto:0, manual:1 (uint8_t) - thrust_manual : thrust auto:0, manual:1 (uint8_t) - - ''' - msg = MAVLink_manual_control_message(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual) - msg.pack(self) - return msg - - def manual_control_send(self, target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual): - ''' - - - target : The system to be controlled (uint8_t) - roll : roll (float) - pitch : pitch (float) - yaw : yaw (float) - thrust : thrust (float) - roll_manual : roll control enabled auto:0, manual:1 (uint8_t) - pitch_manual : pitch auto:0, manual:1 (uint8_t) - yaw_manual : yaw auto:0, manual:1 (uint8_t) - thrust_manual : thrust auto:0, manual:1 (uint8_t) - - ''' - return self.send(self.manual_control_encode(target, roll, pitch, yaw, thrust, roll_manual, pitch_manual, yaw_manual, thrust_manual)) - - def rc_channels_override_encode(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - ''' - The RAW values of the RC channels sent to the MAV to override info - received from the RC radio. A value of -1 means no - change to that channel. A value of 0 means control of - that channel should be released back to the RC radio. - The standard PPM modulation is as follows: 1000 - microseconds: 0%, 2000 microseconds: 100%. Individual - receivers/transmitters might violate this - specification. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - - ''' - msg = MAVLink_rc_channels_override_message(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw) - msg.pack(self) - return msg - - def rc_channels_override_send(self, target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw): - ''' - The RAW values of the RC channels sent to the MAV to override info - received from the RC radio. A value of -1 means no - change to that channel. A value of 0 means control of - that channel should be released back to the RC radio. - The standard PPM modulation is as follows: 1000 - microseconds: 0%, 2000 microseconds: 100%. Individual - receivers/transmitters might violate this - specification. - - target_system : System ID (uint8_t) - target_component : Component ID (uint8_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - - ''' - return self.send(self.rc_channels_override_encode(target_system, target_component, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw)) - - def vfr_hud_encode(self, airspeed, groundspeed, heading, throttle, alt, climb): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - - airspeed : Current airspeed in m/s (float) - groundspeed : Current ground speed in m/s (float) - heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) - throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) - alt : Current altitude (MSL), in meters (float) - climb : Current climb rate in meters/second (float) - - ''' - msg = MAVLink_vfr_hud_message(airspeed, groundspeed, heading, throttle, alt, climb) - msg.pack(self) - return msg - - def vfr_hud_send(self, airspeed, groundspeed, heading, throttle, alt, climb): - ''' - Metrics typically displayed on a HUD for fixed wing aircraft - - airspeed : Current airspeed in m/s (float) - groundspeed : Current ground speed in m/s (float) - heading : Current heading in degrees, in compass units (0..360, 0=north) (int16_t) - throttle : Current throttle setting in integer percent, 0 to 100 (uint16_t) - alt : Current altitude (MSL), in meters (float) - climb : Current climb rate in meters/second (float) - - ''' - return self.send(self.vfr_hud_encode(airspeed, groundspeed, heading, throttle, alt, climb)) - - def command_long_encode(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): - ''' - Send a command with up to four parameters to the MAV - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - command : Command ID, as defined by MAV_CMD enum. (uint16_t) - confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) - param1 : Parameter 1, as defined by MAV_CMD enum. (float) - param2 : Parameter 2, as defined by MAV_CMD enum. (float) - param3 : Parameter 3, as defined by MAV_CMD enum. (float) - param4 : Parameter 4, as defined by MAV_CMD enum. (float) - param5 : Parameter 5, as defined by MAV_CMD enum. (float) - param6 : Parameter 6, as defined by MAV_CMD enum. (float) - param7 : Parameter 7, as defined by MAV_CMD enum. (float) - - ''' - msg = MAVLink_command_long_message(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7) - msg.pack(self) - return msg - - def command_long_send(self, target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7): - ''' - Send a command with up to four parameters to the MAV - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - command : Command ID, as defined by MAV_CMD enum. (uint16_t) - confirmation : 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command) (uint8_t) - param1 : Parameter 1, as defined by MAV_CMD enum. (float) - param2 : Parameter 2, as defined by MAV_CMD enum. (float) - param3 : Parameter 3, as defined by MAV_CMD enum. (float) - param4 : Parameter 4, as defined by MAV_CMD enum. (float) - param5 : Parameter 5, as defined by MAV_CMD enum. (float) - param6 : Parameter 6, as defined by MAV_CMD enum. (float) - param7 : Parameter 7, as defined by MAV_CMD enum. (float) - - ''' - return self.send(self.command_long_encode(target_system, target_component, command, confirmation, param1, param2, param3, param4, param5, param6, param7)) - - def command_ack_encode(self, command, result): - ''' - Report status of a command. Includes feedback wether the command was - executed - - command : Command ID, as defined by MAV_CMD enum. (uint16_t) - result : See MAV_RESULT enum (uint8_t) - - ''' - msg = MAVLink_command_ack_message(command, result) - msg.pack(self) - return msg - - def command_ack_send(self, command, result): - ''' - Report status of a command. Includes feedback wether the command was - executed - - command : Command ID, as defined by MAV_CMD enum. (uint16_t) - result : See MAV_RESULT enum (uint8_t) - - ''' - return self.send(self.command_ack_encode(command, result)) - - def hil_state_encode(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - ''' - Sent from simulation to autopilot. This packet is useful for high - throughput applications such as - hardware in the loop simulations. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - - ''' - msg = MAVLink_hil_state_message(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc) - msg.pack(self) - return msg - - def hil_state_send(self, time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc): - ''' - Sent from simulation to autopilot. This packet is useful for high - throughput applications such as - hardware in the loop simulations. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll : Roll angle (rad) (float) - pitch : Pitch angle (rad) (float) - yaw : Yaw angle (rad) (float) - rollspeed : Roll angular speed (rad/s) (float) - pitchspeed : Pitch angular speed (rad/s) (float) - yawspeed : Yaw angular speed (rad/s) (float) - lat : Latitude, expressed as * 1E7 (int32_t) - lon : Longitude, expressed as * 1E7 (int32_t) - alt : Altitude in meters, expressed as * 1000 (millimeters) (int32_t) - vx : Ground X Speed (Latitude), expressed as m/s * 100 (int16_t) - vy : Ground Y Speed (Longitude), expressed as m/s * 100 (int16_t) - vz : Ground Z Speed (Altitude), expressed as m/s * 100 (int16_t) - xacc : X acceleration (mg) (int16_t) - yacc : Y acceleration (mg) (int16_t) - zacc : Z acceleration (mg) (int16_t) - - ''' - return self.send(self.hil_state_encode(time_usec, roll, pitch, yaw, rollspeed, pitchspeed, yawspeed, lat, lon, alt, vx, vy, vz, xacc, yacc, zacc)) - - def hil_controls_encode(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): - ''' - Sent from autopilot to simulation. Hardware in the loop control - outputs - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll_ailerons : Control output -1 .. 1 (float) - pitch_elevator : Control output -1 .. 1 (float) - yaw_rudder : Control output -1 .. 1 (float) - throttle : Throttle 0 .. 1 (float) - aux1 : Aux 1, -1 .. 1 (float) - aux2 : Aux 2, -1 .. 1 (float) - aux3 : Aux 3, -1 .. 1 (float) - aux4 : Aux 4, -1 .. 1 (float) - mode : System mode (MAV_MODE) (uint8_t) - nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) - - ''' - msg = MAVLink_hil_controls_message(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode) - msg.pack(self) - return msg - - def hil_controls_send(self, time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode): - ''' - Sent from autopilot to simulation. Hardware in the loop control - outputs - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - roll_ailerons : Control output -1 .. 1 (float) - pitch_elevator : Control output -1 .. 1 (float) - yaw_rudder : Control output -1 .. 1 (float) - throttle : Throttle 0 .. 1 (float) - aux1 : Aux 1, -1 .. 1 (float) - aux2 : Aux 2, -1 .. 1 (float) - aux3 : Aux 3, -1 .. 1 (float) - aux4 : Aux 4, -1 .. 1 (float) - mode : System mode (MAV_MODE) (uint8_t) - nav_mode : Navigation mode (MAV_NAV_MODE) (uint8_t) - - ''' - return self.send(self.hil_controls_encode(time_usec, roll_ailerons, pitch_elevator, yaw_rudder, throttle, aux1, aux2, aux3, aux4, mode, nav_mode)) - - def hil_rc_inputs_raw_encode(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): - ''' - Sent from simulation to autopilot. The RAW values of the RC channels - received. The standard PPM modulation is as follows: - 1000 microseconds: 0%, 2000 microseconds: 100%. - Individual receivers/transmitters might violate this - specification. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - chan9_raw : RC channel 9 value, in microseconds (uint16_t) - chan10_raw : RC channel 10 value, in microseconds (uint16_t) - chan11_raw : RC channel 11 value, in microseconds (uint16_t) - chan12_raw : RC channel 12 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - msg = MAVLink_hil_rc_inputs_raw_message(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi) - msg.pack(self) - return msg - - def hil_rc_inputs_raw_send(self, time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi): - ''' - Sent from simulation to autopilot. The RAW values of the RC channels - received. The standard PPM modulation is as follows: - 1000 microseconds: 0%, 2000 microseconds: 100%. - Individual receivers/transmitters might violate this - specification. - - time_usec : Timestamp (microseconds since UNIX epoch or microseconds since system boot) (uint64_t) - chan1_raw : RC channel 1 value, in microseconds (uint16_t) - chan2_raw : RC channel 2 value, in microseconds (uint16_t) - chan3_raw : RC channel 3 value, in microseconds (uint16_t) - chan4_raw : RC channel 4 value, in microseconds (uint16_t) - chan5_raw : RC channel 5 value, in microseconds (uint16_t) - chan6_raw : RC channel 6 value, in microseconds (uint16_t) - chan7_raw : RC channel 7 value, in microseconds (uint16_t) - chan8_raw : RC channel 8 value, in microseconds (uint16_t) - chan9_raw : RC channel 9 value, in microseconds (uint16_t) - chan10_raw : RC channel 10 value, in microseconds (uint16_t) - chan11_raw : RC channel 11 value, in microseconds (uint16_t) - chan12_raw : RC channel 12 value, in microseconds (uint16_t) - rssi : Receive signal strength indicator, 0: 0%, 255: 100% (uint8_t) - - ''' - return self.send(self.hil_rc_inputs_raw_encode(time_usec, chan1_raw, chan2_raw, chan3_raw, chan4_raw, chan5_raw, chan6_raw, chan7_raw, chan8_raw, chan9_raw, chan10_raw, chan11_raw, chan12_raw, rssi)) - - def optical_flow_encode(self, time_usec, sensor_id, flow_x, flow_y, quality, ground_distance): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - - time_usec : Timestamp (UNIX) (uint64_t) - sensor_id : Sensor ID (uint8_t) - flow_x : Flow in pixels in x-sensor direction (int16_t) - flow_y : Flow in pixels in y-sensor direction (int16_t) - quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) - ground_distance : Ground distance in meters (float) - - ''' - msg = MAVLink_optical_flow_message(time_usec, sensor_id, flow_x, flow_y, quality, ground_distance) - msg.pack(self) - return msg - - def optical_flow_send(self, time_usec, sensor_id, flow_x, flow_y, quality, ground_distance): - ''' - Optical flow from a flow sensor (e.g. optical mouse sensor) - - time_usec : Timestamp (UNIX) (uint64_t) - sensor_id : Sensor ID (uint8_t) - flow_x : Flow in pixels in x-sensor direction (int16_t) - flow_y : Flow in pixels in y-sensor direction (int16_t) - quality : Optical flow quality / confidence. 0: bad, 255: maximum quality (uint8_t) - ground_distance : Ground distance in meters (float) - - ''' - return self.send(self.optical_flow_encode(time_usec, sensor_id, flow_x, flow_y, quality, ground_distance)) - - def global_vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - msg = MAVLink_global_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) - msg.pack(self) - return msg - - def global_vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - return self.send(self.global_vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) - - def vision_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - msg = MAVLink_vision_position_estimate_message(usec, x, y, z, roll, pitch, yaw) - msg.pack(self) - return msg - - def vision_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - return self.send(self.vision_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) - - def vision_speed_estimate_encode(self, usec, x, y, z): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X speed (float) - y : Global Y speed (float) - z : Global Z speed (float) - - ''' - msg = MAVLink_vision_speed_estimate_message(usec, x, y, z) - msg.pack(self) - return msg - - def vision_speed_estimate_send(self, usec, x, y, z): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X speed (float) - y : Global Y speed (float) - z : Global Z speed (float) - - ''' - return self.send(self.vision_speed_estimate_encode(usec, x, y, z)) - - def vicon_position_estimate_encode(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - msg = MAVLink_vicon_position_estimate_message(usec, x, y, z, roll, pitch, yaw) - msg.pack(self) - return msg - - def vicon_position_estimate_send(self, usec, x, y, z, roll, pitch, yaw): - ''' - - - usec : Timestamp (milliseconds) (uint64_t) - x : Global X position (float) - y : Global Y position (float) - z : Global Z position (float) - roll : Roll angle in rad (float) - pitch : Pitch angle in rad (float) - yaw : Yaw angle in rad (float) - - ''' - return self.send(self.vicon_position_estimate_encode(usec, x, y, z, roll, pitch, yaw)) - - def memory_vect_encode(self, address, ver, type, value): - ''' - Send raw controller memory. The use of this message is discouraged for - normal packets, but a quite efficient way for testing - new messages and getting experimental debug output. - - address : Starting address of the debug variables (uint16_t) - ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) - type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) - value : Memory contents at specified address (int8_t) - - ''' - msg = MAVLink_memory_vect_message(address, ver, type, value) - msg.pack(self) - return msg - - def memory_vect_send(self, address, ver, type, value): - ''' - Send raw controller memory. The use of this message is discouraged for - normal packets, but a quite efficient way for testing - new messages and getting experimental debug output. - - address : Starting address of the debug variables (uint16_t) - ver : Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below (uint8_t) - type : Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14 (uint8_t) - value : Memory contents at specified address (int8_t) - - ''' - return self.send(self.memory_vect_encode(address, ver, type, value)) - - def debug_vect_encode(self, name, time_usec, x, y, z): - ''' - - - name : Name (char) - time_usec : Timestamp (uint64_t) - x : x (float) - y : y (float) - z : z (float) - - ''' - msg = MAVLink_debug_vect_message(name, time_usec, x, y, z) - msg.pack(self) - return msg - - def debug_vect_send(self, name, time_usec, x, y, z): - ''' - - - name : Name (char) - time_usec : Timestamp (uint64_t) - x : x (float) - y : y (float) - z : z (float) - - ''' - return self.send(self.debug_vect_encode(name, time_usec, x, y, z)) - - def named_value_float_encode(self, time_boot_ms, name, value): - ''' - Send a key-value pair as float. The use of this message is discouraged - for normal packets, but a quite efficient way for - testing new messages and getting experimental debug - output. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - name : Name of the debug variable (char) - value : Floating point value (float) - - ''' - msg = MAVLink_named_value_float_message(time_boot_ms, name, value) - msg.pack(self) - return msg - - def named_value_float_send(self, time_boot_ms, name, value): - ''' - Send a key-value pair as float. The use of this message is discouraged - for normal packets, but a quite efficient way for - testing new messages and getting experimental debug - output. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - name : Name of the debug variable (char) - value : Floating point value (float) - - ''' - return self.send(self.named_value_float_encode(time_boot_ms, name, value)) - - def named_value_int_encode(self, time_boot_ms, name, value): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient - way for testing new messages and getting experimental - debug output. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - name : Name of the debug variable (char) - value : Signed integer value (int32_t) - - ''' - msg = MAVLink_named_value_int_message(time_boot_ms, name, value) - msg.pack(self) - return msg - - def named_value_int_send(self, time_boot_ms, name, value): - ''' - Send a key-value pair as integer. The use of this message is - discouraged for normal packets, but a quite efficient - way for testing new messages and getting experimental - debug output. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - name : Name of the debug variable (char) - value : Signed integer value (int32_t) - - ''' - return self.send(self.named_value_int_encode(time_boot_ms, name, value)) - - def statustext_encode(self, severity, text): - ''' - Status text message. These messages are printed in yellow in the COMM - console of QGroundControl. WARNING: They consume quite - some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages - are buffered on the MCU and sent only at a limited - rate (e.g. 10 Hz). - - severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) - text : Status text message, without null termination character (char) - - ''' - msg = MAVLink_statustext_message(severity, text) - msg.pack(self) - return msg - - def statustext_send(self, severity, text): - ''' - Status text message. These messages are printed in yellow in the COMM - console of QGroundControl. WARNING: They consume quite - some bandwidth, so use only for important status and - error messages. If implemented wisely, these messages - are buffered on the MCU and sent only at a limited - rate (e.g. 10 Hz). - - severity : Severity of status, 0 = info message, 255 = critical fault (uint8_t) - text : Status text message, without null termination character (char) - - ''' - return self.send(self.statustext_encode(severity, text)) - - def debug_encode(self, time_boot_ms, ind, value): - ''' - Send a debug value. The index is used to discriminate between values. - These values show up in the plot of QGroundControl as - DEBUG N. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - ind : index of debug variable (uint8_t) - value : DEBUG value (float) - - ''' - msg = MAVLink_debug_message(time_boot_ms, ind, value) - msg.pack(self) - return msg - - def debug_send(self, time_boot_ms, ind, value): - ''' - Send a debug value. The index is used to discriminate between values. - These values show up in the plot of QGroundControl as - DEBUG N. - - time_boot_ms : Timestamp (milliseconds since system boot) (uint32_t) - ind : index of debug variable (uint8_t) - value : DEBUG value (float) - - ''' - return self.send(self.debug_encode(time_boot_ms, ind, value)) - - def extended_message_encode(self, target_system, target_component, protocol_flags): - ''' - Extended message spacer. - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - protocol_flags : Retransmission / ACK flags (uint8_t) - - ''' - msg = MAVLink_extended_message_message(target_system, target_component, protocol_flags) - msg.pack(self) - return msg - - def extended_message_send(self, target_system, target_component, protocol_flags): - ''' - Extended message spacer. - - target_system : System which should execute the command (uint8_t) - target_component : Component which should execute the command, 0 for all components (uint8_t) - protocol_flags : Retransmission / ACK flags (uint8_t) - - ''' - return self.send(self.extended_message_encode(target_system, target_component, protocol_flags)) - diff --git a/mavlink/share/pyshared/pymavlink/mavutil.py b/mavlink/share/pyshared/pymavlink/mavutil.py deleted file mode 100644 index c0f625214..000000000 --- a/mavlink/share/pyshared/pymavlink/mavutil.py +++ /dev/null @@ -1,678 +0,0 @@ -#!/usr/bin/env python -''' -mavlink python utility functions - -Copyright Andrew Tridgell 2011 -Released under GNU GPL version 3 or later -''' - -import socket, math, struct, time, os, fnmatch, array, sys, errno -from math import * -from mavextra import * - -if os.getenv('MAVLINK10'): - import mavlinkv10 as mavlink -else: - import mavlink - -def evaluate_expression(expression, vars): - '''evaluation an expression''' - try: - v = eval(expression, globals(), vars) - except NameError: - return None - return v - -def evaluate_condition(condition, vars): - '''evaluation a conditional (boolean) statement''' - if condition is None: - return True - v = evaluate_expression(condition, vars) - if v is None: - return False - return v - - -class mavfile(object): - '''a generic mavlink port''' - def __init__(self, fd, address, source_system=255, notimestamps=False): - self.fd = fd - self.address = address - self.messages = { 'MAV' : self } - if mavlink.WIRE_PROTOCOL_VERSION == "1.0": - self.messages['HOME'] = mavlink.MAVLink_gps_raw_int_message(0,0,0,0,0,0,0,0,0,0) - mavlink.MAVLink_waypoint_message = mavlink.MAVLink_mission_item_message - else: - self.messages['HOME'] = mavlink.MAVLink_gps_raw_message(0,0,0,0,0,0,0,0,0) - self.params = {} - self.mav = None - self.target_system = 0 - self.target_component = 0 - self.mav = mavlink.MAVLink(self, srcSystem=source_system) - self.mav.robust_parsing = True - self.logfile = None - self.logfile_raw = None - self.param_fetch_in_progress = False - self.param_fetch_complete = False - self.start_time = time.time() - self.flightmode = "UNKNOWN" - self.timestamp = 0 - self.message_hooks = [] - self.idle_hooks = [] - self.usec = 0 - self.notimestamps = notimestamps - self._timestamp = None - - def recv(self, n=None): - '''default recv method''' - raise RuntimeError('no recv() method supplied') - - def close(self, n=None): - '''default close method''' - raise RuntimeError('no close() method supplied') - - def write(self, buf): - '''default write method''' - raise RuntimeError('no write() method supplied') - - def pre_message(self): - '''default pre message call''' - return - - def post_message(self, msg): - '''default post message call''' - msg._timestamp = time.time() - type = msg.get_type() - self.messages[type] = msg - - if self._timestamp is not None: - if self.notimestamps: - if 'usec' in msg.__dict__: - self.usec = msg.usec / 1.0e6 - msg._timestamp = self.usec - else: - msg._timestamp = self._timestamp - - self.timestamp = msg._timestamp - if type == 'HEARTBEAT': - self.target_system = msg.get_srcSystem() - self.target_component = msg.get_srcComponent() - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.flightmode = mode_string_v10(msg) - elif type == 'PARAM_VALUE': - self.params[str(msg.param_id)] = msg.param_value - if msg.param_index+1 == msg.param_count: - self.param_fetch_in_progress = False - self.param_fetch_complete = True - elif type == 'SYS_STATUS' and mavlink.WIRE_PROTOCOL_VERSION == '0.9': - self.flightmode = mode_string_v09(msg) - elif type == 'GPS_RAW': - if self.messages['HOME'].fix_type < 2: - self.messages['HOME'] = msg - for hook in self.message_hooks: - hook(self, msg) - - - def recv_msg(self): - '''message receive routine''' - self.pre_message() - while True: - n = self.mav.bytes_needed() - s = self.recv(n) - if len(s) == 0 and len(self.mav.buf) == 0: - return None - if self.logfile_raw: - self.logfile_raw.write(str(s)) - msg = self.mav.parse_char(s) - if msg: - self.post_message(msg) - return msg - - def recv_match(self, condition=None, type=None, blocking=False): - '''recv the next MAVLink message that matches the given condition''' - while True: - m = self.recv_msg() - if m is None: - if blocking: - for hook in self.idle_hooks: - hook(self) - time.sleep(0.01) - continue - return None - if type is not None and type != m.get_type(): - continue - if not evaluate_condition(condition, self.messages): - continue - return m - - def setup_logfile(self, logfile, mode='w'): - '''start logging to the given logfile, with timestamps''' - self.logfile = open(logfile, mode=mode) - - def setup_logfile_raw(self, logfile, mode='w'): - '''start logging raw bytes to the given logfile, without timestamps''' - self.logfile_raw = open(logfile, mode=mode) - - def wait_heartbeat(self, blocking=True): - '''wait for a heartbeat so we know the target system IDs''' - return self.recv_match(type='HEARTBEAT', blocking=blocking) - - def param_fetch_all(self): - '''initiate fetch of all parameters''' - if time.time() - getattr(self, 'param_fetch_start', 0) < 2.0: - # don't fetch too often - return - self.param_fetch_start = time.time() - self.param_fetch_in_progress = True - self.mav.param_request_list_send(self.target_system, self.target_component) - - def time_since(self, mtype): - '''return the time since the last message of type mtype was received''' - if not mtype in self.messages: - return time.time() - self.start_time - return time.time() - self.messages[mtype]._timestamp - - def param_set_send(self, parm_name, parm_value, parm_type=None): - '''wrapper for parameter set''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - if parm_type == None: - parm_type = mavlink.MAV_VAR_FLOAT - self.mav.param_set_send(self.target_system, self.target_component, - parm_name, parm_value, parm_type) - else: - self.mav.param_set_send(self.target_system, self.target_component, - parm_name, parm_value) - - def waypoint_request_list_send(self): - '''wrapper for waypoint_request_list_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_request_list_send(self.target_system, self.target_component) - else: - self.mav.waypoint_request_list_send(self.target_system, self.target_component) - - def waypoint_clear_all_send(self): - '''wrapper for waypoint_clear_all_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_clear_all_send(self.target_system, self.target_component) - else: - self.mav.waypoint_clear_all_send(self.target_system, self.target_component) - - def waypoint_request_send(self, seq): - '''wrapper for waypoint_request_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_request_send(self.target_system, self.target_component, seq) - else: - self.mav.waypoint_request_send(self.target_system, self.target_component, seq) - - def waypoint_set_current_send(self, seq): - '''wrapper for waypoint_set_current_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_set_current_send(self.target_system, self.target_component, seq) - else: - self.mav.waypoint_set_current_send(self.target_system, self.target_component, seq) - - def waypoint_count_send(self, seq): - '''wrapper for waypoint_count_send''' - if mavlink.WIRE_PROTOCOL_VERSION == '1.0': - self.mav.mission_count_send(self.target_system, self.target_component, seq) - else: - self.mav.waypoint_count_send(self.target_system, self.target_component, seq) - - -class mavserial(mavfile): - '''a serial mavlink port''' - def __init__(self, device, baud=115200, autoreconnect=False, source_system=255): - import serial - self.baud = baud - self.device = device - self.autoreconnect = autoreconnect - self.port = serial.Serial(self.device, self.baud, timeout=0, - dsrdtr=False, rtscts=False, xonxoff=False) - - try: - fd = self.port.fileno() - except Exception: - fd = None - mavfile.__init__(self, fd, device, source_system=source_system) - - def close(self): - self.port.close() - - def recv(self,n=None): - if n is None: - n = self.mav.bytes_needed() - if self.fd is None: - waiting = self.port.inWaiting() - if waiting < n: - n = waiting - return self.port.read(n) - - def write(self, buf): - try: - return self.port.write(buf) - except OSError: - if self.autoreconnect: - self.reset() - return -1 - - def reset(self): - import serial - self.port.close() - while True: - try: - self.port = serial.Serial(self.device, self.baud, timeout=1, - dsrdtr=False, rtscts=False, xonxoff=False) - try: - self.fd = self.port.fileno() - except Exception: - self.fd = None - return - except Exception: - print("Failed to reopen %s" % self.device) - time.sleep(1) - - -class mavudp(mavfile): - '''a UDP mavlink socket''' - def __init__(self, device, input=True, source_system=255): - a = device.split(':') - if len(a) != 2: - print("UDP ports must be specified as host:port") - sys.exit(1) - self.port = socket.socket(socket.AF_INET, socket.SOCK_DGRAM) - self.udp_server = input - if input: - self.port.bind((a[0], int(a[1]))) - else: - self.destination_addr = (a[0], int(a[1])) - self.port.setblocking(0) - self.last_address = None - mavfile.__init__(self, self.port.fileno(), device, source_system=source_system) - - def close(self): - self.port.close() - - def recv(self,n=None): - try: - data, self.last_address = self.port.recvfrom(300) - except socket.error as e: - if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]: - return "" - raise - return data - - def write(self, buf): - try: - if self.udp_server: - if self.last_address: - self.port.sendto(buf, self.last_address) - else: - self.port.sendto(buf, self.destination_addr) - except socket.error: - pass - - def recv_msg(self): - '''message receive routine for UDP link''' - self.pre_message() - s = self.recv() - if len(s) == 0: - return None - msg = self.mav.parse_buffer(s) - if msg is not None: - for m in msg: - self.post_message(m) - return msg[0] - return None - - -class mavtcp(mavfile): - '''a TCP mavlink socket''' - def __init__(self, device, source_system=255): - a = device.split(':') - if len(a) != 2: - print("TCP ports must be specified as host:port") - sys.exit(1) - self.port = socket.socket(socket.AF_INET, socket.SOCK_STREAM) - self.destination_addr = (a[0], int(a[1])) - self.port.connect(self.destination_addr) - self.port.setblocking(0) - self.port.setsockopt(socket.SOL_TCP, socket.TCP_NODELAY, 1) - mavfile.__init__(self, self.port.fileno(), device, source_system=source_system) - - def close(self): - self.port.close() - - def recv(self,n=None): - if n is None: - n = self.mav.bytes_needed() - try: - data = self.port.recv(n) - except socket.error as e: - if e.errno in [ errno.EAGAIN, errno.EWOULDBLOCK ]: - return "" - raise - return data - - def write(self, buf): - try: - self.port.send(buf) - except socket.error: - pass - - -class mavlogfile(mavfile): - '''a MAVLink logfile reader/writer''' - def __init__(self, filename, planner_format=None, - write=False, append=False, - robust_parsing=True, notimestamps=False, source_system=255): - self.filename = filename - self.writeable = write - self.robust_parsing = robust_parsing - self.planner_format = planner_format - self._two64 = math.pow(2.0, 63) - mode = 'rb' - if self.writeable: - if append: - mode = 'ab' - else: - mode = 'wb' - self.f = open(filename, mode) - self.filesize = os.path.getsize(filename) - self.percent = 0 - mavfile.__init__(self, None, filename, source_system=source_system, notimestamps=notimestamps) - if self.notimestamps: - self._timestamp = 0 - else: - self._timestamp = time.time() - - def close(self): - self.f.close() - - def recv(self,n=None): - if n is None: - n = self.mav.bytes_needed() - return self.f.read(n) - - def write(self, buf): - self.f.write(buf) - - def pre_message(self): - '''read timestamp if needed''' - # read the timestamp - self.percent = (100.0 * self.f.tell()) / self.filesize - if self.notimestamps: - return - if self.planner_format: - tbuf = self.f.read(21) - if len(tbuf) != 21 or tbuf[0] != '-' or tbuf[20] != ':': - raise RuntimeError('bad planner timestamp %s' % tbuf) - hnsec = self._two64 + float(tbuf[0:20]) - t = hnsec * 1.0e-7 # convert to seconds - t -= 719163 * 24 * 60 * 60 # convert to 1970 base - else: - tbuf = self.f.read(8) - if len(tbuf) != 8: - return - (tusec,) = struct.unpack('>Q', tbuf) - t = tusec * 1.0e-6 - self._timestamp = t - - def post_message(self, msg): - '''add timestamp to message''' - # read the timestamp - super(mavlogfile, self).post_message(msg) - if self.planner_format: - self.f.read(1) # trailing newline - self.timestamp = msg._timestamp - -class mavchildexec(mavfile): - '''a MAVLink child processes reader/writer''' - def __init__(self, filename, source_system=255): - from subprocess import Popen, PIPE - import fcntl - - self.filename = filename - self.child = Popen(filename, shell=True, stdout=PIPE, stdin=PIPE) - self.fd = self.child.stdout.fileno() - - fl = fcntl.fcntl(self.fd, fcntl.F_GETFL) - fcntl.fcntl(self.fd, fcntl.F_SETFL, fl | os.O_NONBLOCK) - - fl = fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_GETFL) - fcntl.fcntl(self.child.stdout.fileno(), fcntl.F_SETFL, fl | os.O_NONBLOCK) - - mavfile.__init__(self, self.fd, filename, source_system=source_system) - - def close(self): - self.child.close() - - def recv(self,n=None): - try: - x = self.child.stdout.read(1) - except Exception: - return '' - return x - - def write(self, buf): - self.child.stdin.write(buf) - - -def mavlink_connection(device, baud=115200, source_system=255, - planner_format=None, write=False, append=False, - robust_parsing=True, notimestamps=False, input=True): - '''make a serial or UDP mavlink connection''' - if device.startswith('tcp:'): - return mavtcp(device[4:], source_system=source_system) - if device.startswith('udp:'): - return mavudp(device[4:], input=input, source_system=source_system) - if device.find(':') != -1 and not device.endswith('log'): - return mavudp(device, source_system=source_system, input=input) - if os.path.isfile(device): - if device.endswith(".elf"): - return mavchildexec(device, source_system=source_system) - else: - return mavlogfile(device, planner_format=planner_format, write=write, - append=append, robust_parsing=robust_parsing, notimestamps=notimestamps, - source_system=source_system) - return mavserial(device, baud=baud, source_system=source_system) - -class periodic_event(object): - '''a class for fixed frequency events''' - def __init__(self, frequency): - self.frequency = float(frequency) - self.last_time = time.time() - - def force(self): - '''force immediate triggering''' - self.last_time = 0 - - def trigger(self): - '''return True if we should trigger now''' - tnow = time.time() - if self.last_time + (1.0/self.frequency) <= tnow: - self.last_time = tnow - return True - return False - - -try: - from curses import ascii - have_ascii = True -except: - have_ascii = False - -def is_printable(c): - '''see if a character is printable''' - global have_ascii - if have_ascii: - return ascii.isprint(c) - if isinstance(c, int): - ic = c - else: - ic = ord(c) - return ic >= 32 and ic <= 126 - -def all_printable(buf): - '''see if a string is all printable''' - for c in buf: - if not is_printable(c) and not c in ['\r', '\n', '\t']: - return False - return True - -class SerialPort(object): - '''auto-detected serial port''' - def __init__(self, device, description=None, hwid=None): - self.device = device - self.description = description - self.hwid = hwid - - def __str__(self): - ret = self.device - if self.description is not None: - ret += " : " + self.description - if self.hwid is not None: - ret += " : " + self.hwid - return ret - -def auto_detect_serial_win32(preferred_list=['*']): - '''try to auto-detect serial ports on win32''' - try: - import scanwin32 - list = sorted(scanwin32.comports()) - except: - return [] - ret = [] - for order, port, desc, hwid in list: - for preferred in preferred_list: - if fnmatch.fnmatch(desc, preferred) or fnmatch.fnmatch(hwid, preferred): - ret.append(SerialPort(port, description=desc, hwid=hwid)) - if len(ret) > 0: - return ret - # now the rest - for order, port, desc, hwid in list: - ret.append(SerialPort(port, description=desc, hwid=hwid)) - return ret - - - - -def auto_detect_serial_unix(preferred_list=['*']): - '''try to auto-detect serial ports on win32''' - import glob - glist = glob.glob('/dev/ttyS*') + glob.glob('/dev/ttyUSB*') + glob.glob('/dev/ttyACM*') + glob.glob('/dev/serial/by-id/*') - ret = [] - # try preferred ones first - for d in glist: - for preferred in preferred_list: - if fnmatch.fnmatch(d, preferred): - ret.append(SerialPort(d)) - if len(ret) > 0: - return ret - # now the rest - for d in glist: - ret.append(SerialPort(d)) - return ret - - - -def auto_detect_serial(preferred_list=['*']): - '''try to auto-detect serial port''' - # see if - if os.name == 'nt': - return auto_detect_serial_win32(preferred_list=preferred_list) - return auto_detect_serial_unix(preferred_list=preferred_list) - -def mode_string_v09(msg): - '''mode string for 0.9 protocol''' - mode = msg.mode - nav_mode = msg.nav_mode - - MAV_MODE_UNINIT = 0 - MAV_MODE_MANUAL = 2 - MAV_MODE_GUIDED = 3 - MAV_MODE_AUTO = 4 - MAV_MODE_TEST1 = 5 - MAV_MODE_TEST2 = 6 - MAV_MODE_TEST3 = 7 - - MAV_NAV_GROUNDED = 0 - MAV_NAV_LIFTOFF = 1 - MAV_NAV_HOLD = 2 - MAV_NAV_WAYPOINT = 3 - MAV_NAV_VECTOR = 4 - MAV_NAV_RETURNING = 5 - MAV_NAV_LANDING = 6 - MAV_NAV_LOST = 7 - MAV_NAV_LOITER = 8 - - cmode = (mode, nav_mode) - mapping = { - (MAV_MODE_UNINIT, MAV_NAV_GROUNDED) : "INITIALISING", - (MAV_MODE_MANUAL, MAV_NAV_VECTOR) : "MANUAL", - (MAV_MODE_TEST3, MAV_NAV_VECTOR) : "CIRCLE", - (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED", - (MAV_MODE_TEST1, MAV_NAV_VECTOR) : "STABILIZE", - (MAV_MODE_TEST2, MAV_NAV_LIFTOFF) : "FBWA", - (MAV_MODE_AUTO, MAV_NAV_WAYPOINT) : "AUTO", - (MAV_MODE_AUTO, MAV_NAV_RETURNING) : "RTL", - (MAV_MODE_AUTO, MAV_NAV_LOITER) : "LOITER", - (MAV_MODE_AUTO, MAV_NAV_LIFTOFF) : "TAKEOFF", - (MAV_MODE_AUTO, MAV_NAV_LANDING) : "LANDING", - (MAV_MODE_AUTO, MAV_NAV_HOLD) : "LOITER", - (MAV_MODE_GUIDED, MAV_NAV_VECTOR) : "GUIDED", - (MAV_MODE_GUIDED, MAV_NAV_WAYPOINT) : "GUIDED", - (100, MAV_NAV_VECTOR) : "STABILIZE", - (101, MAV_NAV_VECTOR) : "ACRO", - (102, MAV_NAV_VECTOR) : "ALT_HOLD", - (107, MAV_NAV_VECTOR) : "CIRCLE", - (109, MAV_NAV_VECTOR) : "LAND", - } - if cmode in mapping: - return mapping[cmode] - return "Mode(%s,%s)" % cmode - -def mode_string_v10(msg): - '''mode string for 1.0 protocol, from heartbeat''' - if not msg.base_mode & mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED: - return "Mode(0x%08x)" % msg.base_mode - mapping = { - 0 : 'MANUAL', - 1 : 'CIRCLE', - 2 : 'STABILIZE', - 5 : 'FBWA', - 6 : 'FBWB', - 7 : 'FBWC', - 10 : 'AUTO', - 11 : 'RTL', - 12 : 'LOITER', - 13 : 'TAKEOFF', - 14 : 'LAND', - 15 : 'GUIDED', - 16 : 'INITIALISING' - } - if msg.custom_mode in mapping: - return mapping[msg.custom_mode] - return "Mode(%u)" % msg.custom_mode - - - -class x25crc(object): - '''x25 CRC - based on checksum.h from mavlink library''' - def __init__(self, buf=''): - self.crc = 0xffff - self.accumulate(buf) - - def accumulate(self, buf): - '''add in some more bytes''' - bytes = array.array('B') - if isinstance(buf, array.array): - bytes.extend(buf) - else: - bytes.fromstring(buf) - accum = self.crc - for b in bytes: - tmp = b ^ (accum & 0xff) - tmp = (tmp ^ (tmp<<4)) & 0xFF - accum = (accum>>8) ^ (tmp<<8) ^ (tmp<<3) ^ (tmp>>4) - accum = accum & 0xFFFF - self.crc = accum diff --git a/mavlink/share/pyshared/pymavlink/mavwp.py b/mavlink/share/pyshared/pymavlink/mavwp.py deleted file mode 100644 index 6fd1e10e2..000000000 --- a/mavlink/share/pyshared/pymavlink/mavwp.py +++ /dev/null @@ -1,200 +0,0 @@ -''' -module for loading/saving waypoints -''' - -import os - -if os.getenv('MAVLINK10'): - import mavlinkv10 as mavlink -else: - import mavlink - -class MAVWPError(Exception): - '''MAVLink WP error class''' - def __init__(self, msg): - Exception.__init__(self, msg) - self.message = msg - -class MAVWPLoader(object): - '''MAVLink waypoint loader''' - def __init__(self, target_system=0, target_component=0): - self.wpoints = [] - self.target_system = target_system - self.target_component = target_component - - - def count(self): - '''return number of waypoints''' - return len(self.wpoints) - - def wp(self, i): - '''return a waypoint''' - return self.wpoints[i] - - def add(self, w): - '''add a waypoint''' - w.seq = self.count() - self.wpoints.append(w) - - def remove(self, w): - '''remove a waypoint''' - self.wpoints.remove(w) - - def clear(self): - '''clear waypoint list''' - self.wpoints = [] - - def _read_waypoint_v100(self, line): - '''read a version 100 waypoint''' - cmdmap = { - 2 : mavlink.MAV_CMD_NAV_TAKEOFF, - 3 : mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, - 4 : mavlink.MAV_CMD_NAV_LAND, - 24: mavlink.MAV_CMD_NAV_TAKEOFF, - 26: mavlink.MAV_CMD_NAV_LAND, - 25: mavlink.MAV_CMD_NAV_WAYPOINT , - 27: mavlink.MAV_CMD_NAV_LOITER_UNLIM - } - a = line.split() - if len(a) != 13: - raise MAVWPError("invalid waypoint line with %u values" % len(a)) - w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component, - int(a[0]), # seq - int(a[1]), # frame - int(a[2]), # action - int(a[7]), # current - int(a[12]), # autocontinue - float(a[5]), # param1, - float(a[6]), # param2, - float(a[3]), # param3 - float(a[4]), # param4 - float(a[9]), # x, latitude - float(a[8]), # y, longitude - float(a[10]) # z - ) - if not w.command in cmdmap: - raise MAVWPError("Unknown v100 waypoint action %u" % w.command) - - w.command = cmdmap[w.command] - return w - - def _read_waypoint_v110(self, line): - '''read a version 110 waypoint''' - a = line.split() - if len(a) != 12: - raise MAVWPError("invalid waypoint line with %u values" % len(a)) - w = mavlink.MAVLink_waypoint_message(self.target_system, self.target_component, - int(a[0]), # seq - int(a[2]), # frame - int(a[3]), # command - int(a[1]), # current - int(a[11]), # autocontinue - float(a[4]), # param1, - float(a[5]), # param2, - float(a[6]), # param3 - float(a[7]), # param4 - float(a[8]), # x (latitude) - float(a[9]), # y (longitude) - float(a[10]) # z (altitude) - ) - return w - - - def load(self, filename): - '''load waypoints from a file. - returns number of waypoints loaded''' - f = open(filename, mode='r') - version_line = f.readline().strip() - if version_line == "QGC WPL 100": - readfn = self._read_waypoint_v100 - elif version_line == "QGC WPL 110": - readfn = self._read_waypoint_v110 - else: - f.close() - raise MAVWPError("Unsupported waypoint format '%s'" % version_line) - - self.clear() - - for line in f: - if line.startswith('#'): - continue - line = line.strip() - if not line: - continue - w = readfn(line) - if w is not None: - self.add(w) - f.close() - return len(self.wpoints) - - - def save(self, filename): - '''save waypoints to a file''' - f = open(filename, mode='w') - f.write("QGC WPL 110\n") - for w in self.wpoints: - f.write("%u\t%u\t%u\t%u\t%f\t%f\t%f\t%f\t%f\t%f\t%f\t%u\n" % ( - w.seq, w.current, w.frame, w.command, - w.param1, w.param2, w.param3, w.param4, - w.x, w.y, w.z, w.autocontinue)) - f.close() - - -class MAVFenceError(Exception): - '''MAVLink fence error class''' - def __init__(self, msg): - Exception.__init__(self, msg) - self.message = msg - -class MAVFenceLoader(object): - '''MAVLink geo-fence loader''' - def __init__(self, target_system=0, target_component=0): - self.points = [] - self.target_system = target_system - self.target_component = target_component - - def count(self): - '''return number of points''' - return len(self.points) - - def point(self, i): - '''return a point''' - return self.points[i] - - def add(self, p): - '''add a point''' - self.points.append(p) - - def clear(self): - '''clear point list''' - self.points = [] - - def load(self, filename): - '''load points from a file. - returns number of points loaded''' - f = open(filename, mode='r') - self.clear() - for line in f: - if line.startswith('#'): - continue - line = line.strip() - if not line: - continue - a = line.split() - if len(a) != 2: - raise MAVFenceError("invalid fence point line: %s" % line) - p = mavlink.MAVLink_fence_point_message(self.target_system, self.target_component, - self.count(), 0, float(a[0]), float(a[1])) - self.add(p) - f.close() - for i in range(self.count()): - self.points[i].count = self.count() - return len(self.points) - - - def save(self, filename): - '''save fence points to a file''' - f = open(filename, mode='w') - for p in self.points: - f.write("%f\t%f\n" % (p.lat, p.lng)) - f.close() diff --git a/mavlink/share/pyshared/pymavlink/scanwin32.py b/mavlink/share/pyshared/pymavlink/scanwin32.py deleted file mode 100644 index f90ed5f4d..000000000 --- a/mavlink/share/pyshared/pymavlink/scanwin32.py +++ /dev/null @@ -1,236 +0,0 @@ -#!/usr/bin/env python - -# this is taken from the pySerial documentation at -# http://pyserial.sourceforge.net/examples.html -import ctypes -import re - -def ValidHandle(value): - if value == 0: - raise ctypes.WinError() - return value - -NULL = 0 -HDEVINFO = ctypes.c_int -BOOL = ctypes.c_int -CHAR = ctypes.c_char -PCTSTR = ctypes.c_char_p -HWND = ctypes.c_uint -DWORD = ctypes.c_ulong -PDWORD = ctypes.POINTER(DWORD) -ULONG = ctypes.c_ulong -ULONG_PTR = ctypes.POINTER(ULONG) -#~ PBYTE = ctypes.c_char_p -PBYTE = ctypes.c_void_p - -class GUID(ctypes.Structure): - _fields_ = [ - ('Data1', ctypes.c_ulong), - ('Data2', ctypes.c_ushort), - ('Data3', ctypes.c_ushort), - ('Data4', ctypes.c_ubyte*8), - ] - def __str__(self): - return "{%08x-%04x-%04x-%s-%s}" % ( - self.Data1, - self.Data2, - self.Data3, - ''.join(["%02x" % d for d in self.Data4[:2]]), - ''.join(["%02x" % d for d in self.Data4[2:]]), - ) - -class SP_DEVINFO_DATA(ctypes.Structure): - _fields_ = [ - ('cbSize', DWORD), - ('ClassGuid', GUID), - ('DevInst', DWORD), - ('Reserved', ULONG_PTR), - ] - def __str__(self): - return "ClassGuid:%s DevInst:%s" % (self.ClassGuid, self.DevInst) -PSP_DEVINFO_DATA = ctypes.POINTER(SP_DEVINFO_DATA) - -class SP_DEVICE_INTERFACE_DATA(ctypes.Structure): - _fields_ = [ - ('cbSize', DWORD), - ('InterfaceClassGuid', GUID), - ('Flags', DWORD), - ('Reserved', ULONG_PTR), - ] - def __str__(self): - return "InterfaceClassGuid:%s Flags:%s" % (self.InterfaceClassGuid, self.Flags) - -PSP_DEVICE_INTERFACE_DATA = ctypes.POINTER(SP_DEVICE_INTERFACE_DATA) - -PSP_DEVICE_INTERFACE_DETAIL_DATA = ctypes.c_void_p - -class dummy(ctypes.Structure): - _fields_=[("d1", DWORD), ("d2", CHAR)] - _pack_ = 1 -SIZEOF_SP_DEVICE_INTERFACE_DETAIL_DATA_A = ctypes.sizeof(dummy) - -SetupDiDestroyDeviceInfoList = ctypes.windll.setupapi.SetupDiDestroyDeviceInfoList -SetupDiDestroyDeviceInfoList.argtypes = [HDEVINFO] -SetupDiDestroyDeviceInfoList.restype = BOOL - -SetupDiGetClassDevs = ctypes.windll.setupapi.SetupDiGetClassDevsA -SetupDiGetClassDevs.argtypes = [ctypes.POINTER(GUID), PCTSTR, HWND, DWORD] -SetupDiGetClassDevs.restype = ValidHandle # HDEVINFO - -SetupDiEnumDeviceInterfaces = ctypes.windll.setupapi.SetupDiEnumDeviceInterfaces -SetupDiEnumDeviceInterfaces.argtypes = [HDEVINFO, PSP_DEVINFO_DATA, ctypes.POINTER(GUID), DWORD, PSP_DEVICE_INTERFACE_DATA] -SetupDiEnumDeviceInterfaces.restype = BOOL - -SetupDiGetDeviceInterfaceDetail = ctypes.windll.setupapi.SetupDiGetDeviceInterfaceDetailA -SetupDiGetDeviceInterfaceDetail.argtypes = [HDEVINFO, PSP_DEVICE_INTERFACE_DATA, PSP_DEVICE_INTERFACE_DETAIL_DATA, DWORD, PDWORD, PSP_DEVINFO_DATA] -SetupDiGetDeviceInterfaceDetail.restype = BOOL - -SetupDiGetDeviceRegistryProperty = ctypes.windll.setupapi.SetupDiGetDeviceRegistryPropertyA -SetupDiGetDeviceRegistryProperty.argtypes = [HDEVINFO, PSP_DEVINFO_DATA, DWORD, PDWORD, PBYTE, DWORD, PDWORD] -SetupDiGetDeviceRegistryProperty.restype = BOOL - - -GUID_CLASS_COMPORT = GUID(0x86e0d1e0L, 0x8089, 0x11d0, - (ctypes.c_ubyte*8)(0x9c, 0xe4, 0x08, 0x00, 0x3e, 0x30, 0x1f, 0x73)) - -DIGCF_PRESENT = 2 -DIGCF_DEVICEINTERFACE = 16 -INVALID_HANDLE_VALUE = 0 -ERROR_INSUFFICIENT_BUFFER = 122 -SPDRP_HARDWAREID = 1 -SPDRP_FRIENDLYNAME = 12 -SPDRP_LOCATION_INFORMATION = 13 -ERROR_NO_MORE_ITEMS = 259 - -def comports(available_only=True): - """This generator scans the device registry for com ports and yields - (order, port, desc, hwid). If available_only is true only return currently - existing ports. Order is a helper to get sorted lists. it can be ignored - otherwise.""" - flags = DIGCF_DEVICEINTERFACE - if available_only: - flags |= DIGCF_PRESENT - g_hdi = SetupDiGetClassDevs(ctypes.byref(GUID_CLASS_COMPORT), None, NULL, flags); - #~ for i in range(256): - for dwIndex in range(256): - did = SP_DEVICE_INTERFACE_DATA() - did.cbSize = ctypes.sizeof(did) - - if not SetupDiEnumDeviceInterfaces( - g_hdi, - None, - ctypes.byref(GUID_CLASS_COMPORT), - dwIndex, - ctypes.byref(did) - ): - if ctypes.GetLastError() != ERROR_NO_MORE_ITEMS: - raise ctypes.WinError() - break - - dwNeeded = DWORD() - # get the size - if not SetupDiGetDeviceInterfaceDetail( - g_hdi, - ctypes.byref(did), - None, 0, ctypes.byref(dwNeeded), - None - ): - # Ignore ERROR_INSUFFICIENT_BUFFER - if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER: - raise ctypes.WinError() - # allocate buffer - class SP_DEVICE_INTERFACE_DETAIL_DATA_A(ctypes.Structure): - _fields_ = [ - ('cbSize', DWORD), - ('DevicePath', CHAR*(dwNeeded.value - ctypes.sizeof(DWORD))), - ] - def __str__(self): - return "DevicePath:%s" % (self.DevicePath,) - idd = SP_DEVICE_INTERFACE_DETAIL_DATA_A() - idd.cbSize = SIZEOF_SP_DEVICE_INTERFACE_DETAIL_DATA_A - devinfo = SP_DEVINFO_DATA() - devinfo.cbSize = ctypes.sizeof(devinfo) - if not SetupDiGetDeviceInterfaceDetail( - g_hdi, - ctypes.byref(did), - ctypes.byref(idd), dwNeeded, None, - ctypes.byref(devinfo) - ): - raise ctypes.WinError() - - # hardware ID - szHardwareID = ctypes.create_string_buffer(250) - if not SetupDiGetDeviceRegistryProperty( - g_hdi, - ctypes.byref(devinfo), - SPDRP_HARDWAREID, - None, - ctypes.byref(szHardwareID), ctypes.sizeof(szHardwareID) - 1, - None - ): - # Ignore ERROR_INSUFFICIENT_BUFFER - if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER: - raise ctypes.WinError() - - # friendly name - szFriendlyName = ctypes.create_string_buffer(1024) - if not SetupDiGetDeviceRegistryProperty( - g_hdi, - ctypes.byref(devinfo), - SPDRP_FRIENDLYNAME, - None, - ctypes.byref(szFriendlyName), ctypes.sizeof(szFriendlyName) - 1, - None - ): - # Ignore ERROR_INSUFFICIENT_BUFFER - if ctypes.GetLastError() != ERROR_INSUFFICIENT_BUFFER: - #~ raise ctypes.WinError() - # not getting friendly name for com0com devices, try something else - szFriendlyName = ctypes.create_string_buffer(1024) - if SetupDiGetDeviceRegistryProperty( - g_hdi, - ctypes.byref(devinfo), - SPDRP_LOCATION_INFORMATION, - None, - ctypes.byref(szFriendlyName), ctypes.sizeof(szFriendlyName) - 1, - None - ): - port_name = "\\\\.\\" + szFriendlyName.value - order = None - else: - port_name = szFriendlyName.value - order = None - else: - try: - m = re.search(r"\((.*?(\d+))\)", szFriendlyName.value) - #~ print szFriendlyName.value, m.groups() - port_name = m.group(1) - order = int(m.group(2)) - except AttributeError, msg: - port_name = szFriendlyName.value - order = None - yield order, port_name, szFriendlyName.value, szHardwareID.value - - SetupDiDestroyDeviceInfoList(g_hdi) - - -if __name__ == '__main__': - import serial - print "-"*78 - print "Serial ports" - print "-"*78 - for order, port, desc, hwid in sorted(comports()): - print "%-10s: %s (%s) ->" % (port, desc, hwid), - try: - serial.Serial(port) # test open - except serial.serialutil.SerialException: - print "can't be openend" - else: - print "Ready" - print - # list of all ports the system knows - print "-"*78 - print "All serial ports (registry)" - print "-"*78 - for order, port, desc, hwid in sorted(comports(False)): - print "%-10s: %s (%s)" % (port, desc, hwid) diff --git a/mavlink/share/pyshared/pymavlink/tools/images/gtk-quit.gif b/mavlink/share/pyshared/pymavlink/tools/images/gtk-quit.gif deleted file mode 100644 index 3cce0867b..000000000 Binary files a/mavlink/share/pyshared/pymavlink/tools/images/gtk-quit.gif and /dev/null differ diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-pause.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-playback-pause.gif deleted file mode 100644 index 4dc439b78..000000000 Binary files a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-pause.gif and /dev/null differ diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-start.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-playback-start.gif deleted file mode 100644 index ec4136399..000000000 Binary files a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-start.gif and /dev/null differ diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-stop.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-playback-stop.gif deleted file mode 100644 index 306271a89..000000000 Binary files a/mavlink/share/pyshared/pymavlink/tools/images/media-playback-stop.gif and /dev/null differ diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-seek-backward.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-seek-backward.gif deleted file mode 100644 index 23fcf6d82..000000000 Binary files a/mavlink/share/pyshared/pymavlink/tools/images/media-seek-backward.gif and /dev/null differ diff --git a/mavlink/share/pyshared/pymavlink/tools/images/media-seek-forward.gif b/mavlink/share/pyshared/pymavlink/tools/images/media-seek-forward.gif deleted file mode 100644 index 3439c54fd..000000000 Binary files a/mavlink/share/pyshared/pymavlink/tools/images/media-seek-forward.gif and /dev/null differ diff --git a/mavlink/share/pyshared/pymavlink/tools/images/player_end.gif b/mavlink/share/pyshared/pymavlink/tools/images/player_end.gif deleted file mode 100644 index 9496957d2..000000000 Binary files a/mavlink/share/pyshared/pymavlink/tools/images/player_end.gif and /dev/null differ diff --git a/mavlink/share/pyshared/pymavlink/tools/mavplayback.py b/mavlink/share/pyshared/pymavlink/tools/mavplayback.py deleted file mode 100644 index 033746697..000000000 --- a/mavlink/share/pyshared/pymavlink/tools/mavplayback.py +++ /dev/null @@ -1,246 +0,0 @@ -#!/usr/bin/env python - -''' -play back a mavlink log as a FlightGear FG NET stream, and as a -realtime mavlink stream - -Useful for visualising flights -''' - -import sys, time, os, struct -import Tkinter - -# allow import from the parent directory, where mavlink.py is -sys.path.insert(0, os.path.join(os.path.dirname(os.path.realpath(__file__)), '..')) - -import fgFDM - -from optparse import OptionParser -parser = OptionParser("mavplayback.py [options]") - -parser.add_option("--planner",dest="planner", action='store_true', help="use planner file format") -parser.add_option("--condition",dest="condition", default=None, help="select packets by condition") -parser.add_option("--gpsalt", action='store_true', default=False, help="Use GPS altitude") -parser.add_option("--mav10", action='store_true', default=False, help="Use MAVLink protocol 1.0") -parser.add_option("--out", help="MAVLink output port (IP:port)", - action='append', default=['127.0.0.1:14550']) -parser.add_option("--fgout", action='append', default=['127.0.0.1:5503'], - help="flightgear FDM NET output (IP:port)") -parser.add_option("--baudrate", type='int', default=57600, help='baud rate') -(opts, args) = parser.parse_args() - -if opts.mav10: - os.environ['MAVLINK10'] = '1' -import mavutil - -if len(args) < 1: - parser.print_help() - sys.exit(1) - -filename = args[0] - - -def LoadImage(filename): - '''return an image from the images/ directory''' - app_dir = os.path.dirname(os.path.realpath(__file__)) - path = os.path.join(app_dir, 'files/images', filename) - return Tkinter.PhotoImage(file=path) - - -class App(): - def __init__(self, filename): - self.root = Tkinter.Tk() - - self.filesize = os.path.getsize(filename) - self.filepos = 0.0 - - self.mlog = mavutil.mavlink_connection(filename, planner_format=opts.planner, - robust_parsing=True) - self.mout = [] - for m in opts.out: - self.mout.append(mavutil.mavlink_connection(m, input=False, baud=opts.baudrate)) - - self.fgout = [] - for f in opts.fgout: - self.fgout.append(mavutil.mavudp(f, input=False)) - - self.fdm = fgFDM.fgFDM() - - self.msg = self.mlog.recv_match(condition=opts.condition) - if self.msg is None: - sys.exit(1) - self.last_timestamp = getattr(self.msg, '_timestamp') - - self.paused = False - - self.topframe = Tkinter.Frame(self.root) - self.topframe.pack(side=Tkinter.TOP) - - self.frame = Tkinter.Frame(self.root) - self.frame.pack(side=Tkinter.LEFT) - - self.slider = Tkinter.Scale(self.topframe, from_=0, to=1.0, resolution=0.01, - orient=Tkinter.HORIZONTAL, command=self.slew) - self.slider.pack(side=Tkinter.LEFT) - - self.clock = Tkinter.Label(self.topframe,text="") - self.clock.pack(side=Tkinter.RIGHT) - - self.playback = Tkinter.Spinbox(self.topframe, from_=0, to=20, increment=0.1, width=3) - self.playback.pack(side=Tkinter.BOTTOM) - self.playback.delete(0, "end") - self.playback.insert(0, 1) - - self.buttons = {} - self.button('quit', 'gtk-quit.gif', self.frame.quit) - self.button('pause', 'media-playback-pause.gif', self.pause) - self.button('rewind', 'media-seek-backward.gif', self.rewind) - self.button('forward', 'media-seek-forward.gif', self.forward) - self.button('status', 'Status', self.status) - self.flightmode = Tkinter.Label(self.frame,text="") - self.flightmode.pack(side=Tkinter.RIGHT) - - self.next_message() - self.root.mainloop() - - def button(self, name, filename, command): - '''add a button''' - try: - img = LoadImage(filename) - b = Tkinter.Button(self.frame, image=img, command=command) - b.image = img - except Exception: - b = Tkinter.Button(self.frame, text=filename, command=command) - b.pack(side=Tkinter.LEFT) - self.buttons[name] = b - - - def pause(self): - '''pause playback''' - self.paused = not self.paused - - def rewind(self): - '''rewind 10%''' - pos = int(self.mlog.f.tell() - 0.1*self.filesize) - if pos < 0: - pos = 0 - self.mlog.f.seek(pos) - self.find_message() - - def forward(self): - '''forward 10%''' - pos = int(self.mlog.f.tell() + 0.1*self.filesize) - if pos > self.filesize: - pos = self.filesize - 2048 - self.mlog.f.seek(pos) - self.find_message() - - def status(self): - '''show status''' - for m in sorted(self.mlog.messages.keys()): - print(str(self.mlog.messages[m])) - - - - def find_message(self): - '''find the next valid message''' - while True: - self.msg = self.mlog.recv_match(condition=opts.condition) - if self.msg is not None and self.msg.get_type() != 'BAD_DATA': - break - if self.mlog.f.tell() > self.filesize - 10: - self.paused = True - break - self.last_timestamp = getattr(self.msg, '_timestamp') - - def slew(self, value): - '''move to a given position in the file''' - if float(value) != self.filepos: - pos = float(value) * self.filesize - self.mlog.f.seek(int(pos)) - self.find_message() - - - def next_message(self): - '''called as each msg is ready''' - - msg = self.msg - if msg is None: - self.paused = True - - if self.paused: - self.root.after(100, self.next_message) - return - - speed = float(self.playback.get()) - timestamp = getattr(msg, '_timestamp') - - now = time.strftime("%H:%M:%S", time.localtime(timestamp)) - self.clock.configure(text=now) - - if speed == 0.0: - self.root.after(200, self.next_message) - else: - self.root.after(int(1000*(timestamp - self.last_timestamp) / speed), self.next_message) - self.last_timestamp = timestamp - - while True: - self.msg = self.mlog.recv_match(condition=opts.condition) - if self.msg is None and self.mlog.f.tell() > self.filesize - 10: - self.paused = True - return - if self.msg is not None and self.msg.get_type() != "BAD_DATA": - break - - pos = float(self.mlog.f.tell()) / self.filesize - self.slider.set(pos) - self.filepos = self.slider.get() - - if msg.get_type() != "BAD_DATA": - for m in self.mout: - m.write(msg.get_msgbuf().tostring()) - - if msg.get_type() == "GPS_RAW": - self.fdm.set('latitude', msg.lat, units='degrees') - self.fdm.set('longitude', msg.lon, units='degrees') - if opts.gpsalt: - self.fdm.set('altitude', msg.alt, units='meters') - - if msg.get_type() == "VFR_HUD": - if not opts.gpsalt: - self.fdm.set('altitude', msg.alt, units='meters') - self.fdm.set('num_engines', 1) - self.fdm.set('vcas', msg.airspeed, units='mps') - - if msg.get_type() == "ATTITUDE": - self.fdm.set('phi', msg.roll, units='radians') - self.fdm.set('theta', msg.pitch, units='radians') - self.fdm.set('psi', msg.yaw, units='radians') - self.fdm.set('phidot', msg.rollspeed, units='rps') - self.fdm.set('thetadot', msg.pitchspeed, units='rps') - self.fdm.set('psidot', msg.yawspeed, units='rps') - - if msg.get_type() == "RC_CHANNELS_SCALED": - self.fdm.set("right_aileron", msg.chan1_scaled*0.0001) - self.fdm.set("left_aileron", -msg.chan1_scaled*0.0001) - self.fdm.set("rudder", msg.chan4_scaled*0.0001) - self.fdm.set("elevator", msg.chan2_scaled*0.0001) - self.fdm.set('rpm', msg.chan3_scaled*0.01) - - if msg.get_type() == 'STATUSTEXT': - print("APM: %s" % msg.text) - - if msg.get_type() == 'SYS_STATUS': - self.flightmode.configure(text=self.mlog.flightmode) - - if msg.get_type() == "BAD_DATA": - if mavutil.all_printable(msg.data): - sys.stdout.write(msg.data) - sys.stdout.flush() - - if self.fdm.get('latitude') != 0: - for f in self.fgout: - f.write(self.fdm.pack()) - - -app=App(filename) -- cgit v1.2.3 From b74d4e2ba76d1fa3d6d099b63192b180b1af0a39 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 7 Jul 2014 16:59:44 +0200 Subject: Added NuttX submodule --- .gitignore | 1 - .gitmodules | 3 +++ NuttX | 1 + 3 files changed, 4 insertions(+), 1 deletion(-) create mode 160000 NuttX diff --git a/.gitignore b/.gitignore index afd63e06a..8b09e4783 100644 --- a/.gitignore +++ b/.gitignore @@ -29,7 +29,6 @@ mavlink/include/mavlink/v0.9/ /nuttx-configs/px4io-v1/src/.depend /nuttx-configs/px4io-v1/src/Make.dep /nuttx-configs/px4io-v1/src/libboard.a -/NuttX /Documentation/doxy.log /Documentation/html/ /Documentation/doxygen*objdb*tmp diff --git a/.gitmodules b/.gitmodules index c5116c1cb..fe2d8713a 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,3 +1,6 @@ [submodule "mavlink/include/mavlink/v1.0"] path = mavlink/include/mavlink/v1.0 url = https://github.com/mavlink/c_library.git +[submodule "NuttX"] + path = NuttX + url = git://github.com/PX4/NuttX.git diff --git a/NuttX b/NuttX new file mode 160000 index 000000000..2a94cc8e5 --- /dev/null +++ b/NuttX @@ -0,0 +1 @@ +Subproject commit 2a94cc8e5babb7d5661aedc09201239d39644332 -- cgit v1.2.3 From 6c5c6ba9ee6cfff9ea748f812902922a5c7addba Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 7 Jul 2014 17:03:07 +0200 Subject: Add proper NuttX submodule checks --- Makefile | 10 ++++++---- Tools/check_submodules.sh | 8 ++++++++ 2 files changed, 14 insertions(+), 4 deletions(-) diff --git a/Makefile b/Makefile index 0a8562251..7ea74eaae 100644 --- a/Makefile +++ b/Makefile @@ -104,7 +104,7 @@ DESIRED_FIRMWARES = $(foreach config,$(CONFIGS),$(IMAGE_DIR)$(config).px4) STAGED_FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(IMAGE_DIR)$(config).px4) FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(BUILD_DIR)$(config).build/firmware.px4) -all: $(DESIRED_FIRMWARES) +all: checksubmodules $(DESIRED_FIRMWARES) # # Copy FIRMWARES into the image directory. @@ -210,9 +210,11 @@ menuconfig: endif $(NUTTX_SRC): - @$(ECHO) "" - @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." - @$(ECHO) "" + $(Q) if [ -d $(NUTTX_SRC) ]; then ./Tools/check_submodules.sh; else echo ""; echo ""; echo "NuttX submodule missing, doing auto checkout"; git submodule init; git submodule update; fi + +.PHONY: checksubmodules +checksubmodules: + $(Q) if [ -d $(MAVLINK_SRC) ]; then ./Tools/check_submodules.sh; else echo ""; echo ""; echo "MAVLink submodule missing, doing auto checkout"; git submodule init; git submodule update; fi # # Testing targets diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index 52ea7a146..c431e8225 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -7,4 +7,12 @@ else exit 1 fi +STATUSRETVAL=$(git status --porcelain | grep -i "M NuttX") +if [ "$STATUSRETVAL" == "" ]; then + echo "checked NuttX submodule, correct version found" +else + echo "NuttX sub repo not at correct version. Try 'git submodule update'" + exit 1 +fi + exit 0 -- cgit v1.2.3 From 4c2cc65ca63141839ac4036cb8704b7ee7f27cb1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 7 Jul 2014 17:18:54 +0200 Subject: Cleaning up sub modules --- .gitmodules | 5 ++++- Makefile | 10 ++++++---- Tools/check_submodules.sh | 8 ++++++++ makefiles/setup.mk | 1 + mavlink/include/mavlink/v1.0 | 1 + 5 files changed, 20 insertions(+), 5 deletions(-) create mode 160000 mavlink/include/mavlink/v1.0 diff --git a/.gitmodules b/.gitmodules index c5116c1cb..e352e15f5 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,3 +1,6 @@ -[submodule "mavlink/include/mavlink/v1.0"] +[submodule "mavlink"] path = mavlink/include/mavlink/v1.0 url = https://github.com/mavlink/c_library.git +[submodule "mavlink/include/mavlink/v1.0"] + path = mavlink/include/mavlink/v1.0 + url = git://github.com/mavlink/c_library.git diff --git a/Makefile b/Makefile index 0a8562251..7ea74eaae 100644 --- a/Makefile +++ b/Makefile @@ -104,7 +104,7 @@ DESIRED_FIRMWARES = $(foreach config,$(CONFIGS),$(IMAGE_DIR)$(config).px4) STAGED_FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(IMAGE_DIR)$(config).px4) FIRMWARES = $(foreach config,$(KNOWN_CONFIGS),$(BUILD_DIR)$(config).build/firmware.px4) -all: $(DESIRED_FIRMWARES) +all: checksubmodules $(DESIRED_FIRMWARES) # # Copy FIRMWARES into the image directory. @@ -210,9 +210,11 @@ menuconfig: endif $(NUTTX_SRC): - @$(ECHO) "" - @$(ECHO) "NuttX sources missing - clone https://github.com/PX4/NuttX.git and try again." - @$(ECHO) "" + $(Q) if [ -d $(NUTTX_SRC) ]; then ./Tools/check_submodules.sh; else echo ""; echo ""; echo "NuttX submodule missing, doing auto checkout"; git submodule init; git submodule update; fi + +.PHONY: checksubmodules +checksubmodules: + $(Q) if [ -d $(MAVLINK_SRC) ]; then ./Tools/check_submodules.sh; else echo ""; echo ""; echo "MAVLink submodule missing, doing auto checkout"; git submodule init; git submodule update; fi # # Testing targets diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index 52ea7a146..c431e8225 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -7,4 +7,12 @@ else exit 1 fi +STATUSRETVAL=$(git status --porcelain | grep -i "M NuttX") +if [ "$STATUSRETVAL" == "" ]; then + echo "checked NuttX submodule, correct version found" +else + echo "NuttX sub repo not at correct version. Try 'git submodule update'" + exit 1 +fi + exit 0 diff --git a/makefiles/setup.mk b/makefiles/setup.mk index 183b143d6..6a092ef6b 100644 --- a/makefiles/setup.mk +++ b/makefiles/setup.mk @@ -46,6 +46,7 @@ export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src)/ export PX4_LIB_DIR = $(abspath $(PX4_BASE)/src/lib)/ export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/ export NUTTX_SRC = $(abspath $(PX4_BASE)/NuttX/nuttx)/ +export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink/include/mavlink/v1.0)/ export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/NuttX/apps)/ export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink)/ export ROMFS_SRC = $(abspath $(PX4_BASE)/ROMFS)/ diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 new file mode 160000 index 000000000..45a71d656 --- /dev/null +++ b/mavlink/include/mavlink/v1.0 @@ -0,0 +1 @@ +Subproject commit 45a71d6564bc5c47ed97d620089e17ca48bab73f -- cgit v1.2.3 From 9886bb8ca09dbf8a4b7fdd22e6d2dec9f9854eb9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 7 Jul 2014 17:20:32 +0200 Subject: Fixed .gitmodules --- .gitmodules | 3 --- 1 file changed, 3 deletions(-) diff --git a/.gitmodules b/.gitmodules index e352e15f5..937db7cc6 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,6 +1,3 @@ -[submodule "mavlink"] - path = mavlink/include/mavlink/v1.0 - url = https://github.com/mavlink/c_library.git [submodule "mavlink/include/mavlink/v1.0"] path = mavlink/include/mavlink/v1.0 url = git://github.com/mavlink/c_library.git -- cgit v1.2.3 From 72ccbe9c4ed304997fa5a4fdbf4bd668c69c35b0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 7 Jul 2014 17:35:47 +0200 Subject: Fixed check tools --- Makefile | 4 ++-- Tools/check_submodules.sh | 36 ++++++++++++++++++++++++++---------- 2 files changed, 28 insertions(+), 12 deletions(-) diff --git a/Makefile b/Makefile index 7ea74eaae..7703cc04e 100644 --- a/Makefile +++ b/Makefile @@ -210,11 +210,11 @@ menuconfig: endif $(NUTTX_SRC): - $(Q) if [ -d $(NUTTX_SRC) ]; then ./Tools/check_submodules.sh; else echo ""; echo ""; echo "NuttX submodule missing, doing auto checkout"; git submodule init; git submodule update; fi + $(Q) (./Tools/check_submodules.sh) .PHONY: checksubmodules checksubmodules: - $(Q) if [ -d $(MAVLINK_SRC) ]; then ./Tools/check_submodules.sh; else echo ""; echo ""; echo "MAVLink submodule missing, doing auto checkout"; git submodule init; git submodule update; fi + $(Q) (./Tools/check_submodules.sh) # # Testing targets diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index c431e8225..d31c1588c 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -1,18 +1,34 @@ #!/bin/sh -STATUSRETVAL=$(git status --porcelain | grep -i "M mavlink/include/mavlink/v1.0") -if [ "$STATUSRETVAL" == "" ]; then - echo "checked mavlink submodule, correct version found" + +if [ -d NuttX/nuttx ]; + then + STATUSRETVAL=$(git status --porcelain | grep -i "mavlink/include/mavlink/v1.0") + if [ "$STATUSRETVAL" == "" ]; then + echo "Checked mavlink submodule, correct version found" + else + echo "mavlink sub repo not at correct version. Try 'git submodule update'" + echo "or follow instructions on http://pixhawk.org/dev/git/submodules" + exit 1 + fi else - echo "mavlink sub repo not at correct version. Try 'git submodule update'" - exit 1 + git submodule init; + git submodule update; fi -STATUSRETVAL=$(git status --porcelain | grep -i "M NuttX") -if [ "$STATUSRETVAL" == "" ]; then - echo "checked NuttX submodule, correct version found" + +if [ -d mavlink/include/mavlink/v1.0 ]; + then + STATUSRETVAL=$(git status --porcelain | grep -i "NuttX") + if [ "$STATUSRETVAL" == "" ]; then + echo "Checked NuttX submodule, correct version found" + else + echo "NuttX sub repo not at correct version. Try 'git submodule update'" + echo "or follow instructions on http://pixhawk.org/dev/git/submodules" + exit 1 + fi else - echo "NuttX sub repo not at correct version. Try 'git submodule update'" - exit 1 + git submodule init; + git submodule update; fi exit 0 -- cgit v1.2.3 From cd9f4f33a593e8eea8a0314b776d1ad3ef847462 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 7 Jul 2014 17:51:30 +0200 Subject: Turn instructions into a makefile command, allowing Windows GUI kids to create a make target in Eclipse just for this --- Makefile | 4 ++++ Tools/check_submodules.sh | 4 ++-- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 7703cc04e..8ec5277e2 100644 --- a/Makefile +++ b/Makefile @@ -216,6 +216,10 @@ $(NUTTX_SRC): checksubmodules: $(Q) (./Tools/check_submodules.sh) +.PHONY: updatesubmodules +updatesubmodules: + $(Q) (git submodule update) + # # Testing targets # diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index d31c1588c..1156490d7 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -6,7 +6,7 @@ if [ -d NuttX/nuttx ]; if [ "$STATUSRETVAL" == "" ]; then echo "Checked mavlink submodule, correct version found" else - echo "mavlink sub repo not at correct version. Try 'git submodule update'" + echo "mavlink sub repo not at correct version. Try 'make updatesubmodules'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" exit 1 fi @@ -22,7 +22,7 @@ if [ -d mavlink/include/mavlink/v1.0 ]; if [ "$STATUSRETVAL" == "" ]; then echo "Checked NuttX submodule, correct version found" else - echo "NuttX sub repo not at correct version. Try 'git submodule update'" + echo "NuttX sub repo not at correct version. Try 'make updatesubmodules'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" exit 1 fi -- cgit v1.2.3 From 3b06a74074f71c0700c6e7e9b56954213142aaeb Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Mon, 7 Jul 2014 18:18:13 +0200 Subject: navigator: adapt offboard class to new NavigatorMode API --- src/modules/navigator/offboard.cpp | 27 ++++++++++++++++----------- src/modules/navigator/offboard.h | 16 +++------------- 2 files changed, 19 insertions(+), 24 deletions(-) diff --git a/src/modules/navigator/offboard.cpp b/src/modules/navigator/offboard.cpp index ef7d11a03..dcb5c6000 100644 --- a/src/modules/navigator/offboard.cpp +++ b/src/modules/navigator/offboard.cpp @@ -67,17 +67,27 @@ Offboard::~Offboard() { } -bool -Offboard::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) +void +Offboard::on_inactive() +{ +} + +void +Offboard::on_activation() +{ +} + +void +Offboard::on_active() { + struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); + bool updated; orb_check(_navigator->get_offboard_control_sp_sub(), &updated); if (updated) { update_offboard_control_setpoint(); } - bool changed = false; - /* copy offboard setpoints to the corresponding topics */ if (_navigator->get_control_mode()->flag_control_position_enabled && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_POSITION) { @@ -91,7 +101,7 @@ Offboard::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) pos_sp_triplet->current.valid = true; pos_sp_triplet->current.position_valid = true; - changed = true; + _navigator->set_position_setpoint_triplet_updated(); } else if (_navigator->get_control_mode()->flag_control_velocity_enabled && _offboard_control_sp.mode == OFFBOARD_CONTROL_MODE_DIRECT_VELOCITY) { @@ -105,16 +115,11 @@ Offboard::on_active(struct position_setpoint_triplet_s *pos_sp_triplet) pos_sp_triplet->current.valid = true; pos_sp_triplet->current.velocity_valid = true; - changed = true; + _navigator->set_position_setpoint_triplet_updated(); } - return changed; } -void -Offboard::on_inactive() -{ -} void Offboard::update_offboard_control_setpoint() diff --git a/src/modules/navigator/offboard.h b/src/modules/navigator/offboard.h index 4d415dddb..66b923bdb 100644 --- a/src/modules/navigator/offboard.h +++ b/src/modules/navigator/offboard.h @@ -54,25 +54,15 @@ class Navigator; class Offboard : public NavigatorMode { public: - /** - * Constructor - */ Offboard(Navigator *navigator, const char *name); - /** - * Destructor - */ ~Offboard(); - /** - * This function is called while the mode is inactive - */ virtual void on_inactive(); - /** - * This function is called while the mode is active - */ - virtual bool on_active(struct position_setpoint_triplet_s *pos_sp_triplet); + virtual void on_activation(); + + virtual void on_active(); private: void update_offboard_control_setpoint(); -- cgit v1.2.3 From f5c14ff140804b351464e53ec264945f9bcd48f3 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 7 Jul 2014 10:17:39 -0700 Subject: Turn off noisier logging --- src/modules/mavlink/mavlink_ftp.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index 2da381a2d..e0a52f393 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -210,7 +210,7 @@ MavlinkFTP::_workList(Request *req) return kErrNotDir; } - printf("FTP: list %s offset %d\n", dirPath, hdr->offset); + printf("FTP: list %s offset %d\n", dirPath, hdr->offset); ErrorCode errorCode = kErrNone; struct dirent entry, *result = nullptr; @@ -222,7 +222,7 @@ MavlinkFTP::_workList(Request *req) for (;;) { // read the directory entry if (readdir_r(dp, &entry, &result)) { - printf("FTP: list %s readdir_r failure\n", dirPath); + printf("FTP: list %s readdir_r failure\n", dirPath); errorCode = kErrIO; break; } @@ -258,7 +258,7 @@ MavlinkFTP::_workList(Request *req) // copy the name, which we know will fit strcpy((char *)&hdr->data[offset], entry.d_name); - printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]); + //printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]); offset += strlen(entry.d_name) + 1; } -- cgit v1.2.3 From 2eb018b2730d5b3ceeca430aabbf39cf560ce9fc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 7 Jul 2014 22:20:55 +0200 Subject: bugfixes for checks and tools --- Makefile | 1 + Tools/check_submodules.sh | 12 ++++++------ 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/Makefile b/Makefile index 8ec5277e2..8bf96ca23 100644 --- a/Makefile +++ b/Makefile @@ -218,6 +218,7 @@ checksubmodules: .PHONY: updatesubmodules updatesubmodules: + $(Q) (git submodule init) $(Q) (git submodule update) # diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index 1156490d7..fb180ef47 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -2,11 +2,11 @@ if [ -d NuttX/nuttx ]; then - STATUSRETVAL=$(git status --porcelain | grep -i "mavlink/include/mavlink/v1.0") + STATUSRETVAL=$(git status --porcelain | grep -i "NuttX") if [ "$STATUSRETVAL" == "" ]; then - echo "Checked mavlink submodule, correct version found" + echo "Checked NuttX submodule, correct version found" else - echo "mavlink sub repo not at correct version. Try 'make updatesubmodules'" + echo "NuttX sub repo not at correct version. Try 'make updatesubmodules'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" exit 1 fi @@ -18,11 +18,11 @@ fi if [ -d mavlink/include/mavlink/v1.0 ]; then - STATUSRETVAL=$(git status --porcelain | grep -i "NuttX") + STATUSRETVAL=$(git status --porcelain | grep -i "mavlink/include/mavlink/v1.0") if [ "$STATUSRETVAL" == "" ]; then - echo "Checked NuttX submodule, correct version found" + echo "Checked mavlink submodule, correct version found" else - echo "NuttX sub repo not at correct version. Try 'make updatesubmodules'" + echo "mavlink sub repo not at correct version. Try 'make updatesubmodules'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" exit 1 fi -- cgit v1.2.3 From 680ebf29c3f8298e63d4c4d9c9076464e6f4b3c1 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 7 Jul 2014 15:11:46 -0700 Subject: Fix compiler warnings --- makefiles/toolchain_gnu-arm-eabi.mk | 6 +++++- src/modules/ekf_att_pos_estimator/estimator_23states.cpp | 6 +----- src/modules/navigator/mission.cpp | 8 ++++---- src/modules/navigator/mission_block.cpp | 4 ++-- src/modules/uORB/topics/telemetry_status.h | 10 ++++++++++ src/systemcmds/param/param.c | 1 - src/systemcmds/tests/test_mathlib.cpp | 2 ++ 7 files changed, 24 insertions(+), 13 deletions(-) diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk index 808b635bb..d8d45d34e 100644 --- a/makefiles/toolchain_gnu-arm-eabi.mk +++ b/makefiles/toolchain_gnu-arm-eabi.mk @@ -139,7 +139,11 @@ ARCHWARNINGS = -Wall \ -Werror=format-security \ -Werror=array-bounds \ -Wfatal-errors \ - -Wformat=1 + -Wformat=1 \ + -Werror=unused-but-set-variable \ + -Werror=unused-variable \ + -Werror=double-promotion \ + -Werror=reorder # -Wcast-qual - generates spurious noreturn attribute warnings, try again later # -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code # -Wcast-align - would help catch bad casts in some cases, but generates too many false positives diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index 973de1382..f33a1d780 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -1742,7 +1742,6 @@ void AttPosEKF::FuseOptFlow() static float vd = 0.0f; static float pd = 0.0f; static float ptd = 0.0f; - static Vector3f delAng; static float R_LOS = 0.01f; static float losPred[2]; @@ -1820,9 +1819,6 @@ void AttPosEKF::FuseOptFlow() // calculate relative velocity in sensor frame relVelSensor = Tns*velNED_local; - // calculate delta angles in sensor axes - Vector3f delAngRel = Tbs*delAng; - // divide velocity by range and include angular rate effects to get predicted angular LOS rates relative to X and Y axes losPred[0] = relVelSensor.y/range; losPred[1] = -relVelSensor.x/range; @@ -1959,7 +1955,7 @@ void AttPosEKF::FuseOptFlow() } // normalise the quaternion states float quatMag = sqrt(states[0]*states[0] + states[1]*states[1] + states[2]*states[2] + states[3]*states[3]); - if (quatMag > 1e-12) + if (quatMag > 1e-12f) { for (uint8_t j= 0; j<=3; j++) { diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index cf6a764bf..d39ca6cf9 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -65,11 +65,11 @@ Mission::Mission(Navigator *navigator, const char *name) : _offboard_mission({0}), _current_onboard_mission_index(-1), _current_offboard_mission_index(-1), + _need_takeoff(true), + _takeoff(false), _mission_result_pub(-1), _mission_result({0}), - _mission_type(MISSION_TYPE_NONE), - _need_takeoff(true), - _takeoff(false) + _mission_type(MISSION_TYPE_NONE) { /* load initial params */ updateParams(); @@ -334,7 +334,7 @@ Mission::set_mission_items() takeoff_alt = fmaxf(takeoff_alt, _navigator->get_home_position()->alt + _param_takeoff_alt.get()); } - mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: takeoff to %.1fm above home", takeoff_alt - _navigator->get_home_position()->alt); + mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: takeoff to %.1fm above home", (double)(takeoff_alt - _navigator->get_home_position()->alt)); _mission_item.lat = _navigator->get_global_position()->lat; _mission_item.lon = _navigator->get_global_position()->lon; diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index a1c6f09d0..4adf77dce 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -57,10 +57,10 @@ MissionBlock::MissionBlock(Navigator *navigator, const char *name) : NavigatorMode(navigator, name), + _mission_item({0}), _waypoint_position_reached(false), _waypoint_yaw_reached(false), - _time_first_inside_orbit(0), - _mission_item({0}) + _time_first_inside_orbit(0) { } diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h index c4b99d520..3347724a5 100644 --- a/src/modules/uORB/topics/telemetry_status.h +++ b/src/modules/uORB/topics/telemetry_status.h @@ -86,4 +86,14 @@ static const struct orb_metadata *telemetry_status_orb_id[TELEMETRY_STATUS_ORB_I ORB_ID(telemetry_status_3), }; +// This is a hack to quiet an unused-variable warning for when telemetry_status.h is +// included but telemetry_status_orb_id is not referenced. The inline works if you +// choose to use it, but you can continue to just directly index into the array as well. +// If you don't use the inline this ends up being a no-op with no additional code emitted. +extern inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index); +extern inline const struct orb_metadata *telemetry_status_orb_id_lookup(size_t index) +{ + return telemetry_status_orb_id[index]; +} + #endif /* TOPIC_TELEMETRY_STATUS_H */ diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c index 235ab7186..28e1b108b 100644 --- a/src/systemcmds/param/param.c +++ b/src/systemcmds/param/param.c @@ -231,7 +231,6 @@ do_show_print(void *arg, param_t param) /* start search */ const char *ss = search_string; const char *pp = p_name; - bool mismatch = false; /* XXX this comparison is only ok for trailing wildcards */ while (*ss != '\0' && *pp != '\0') { diff --git a/src/systemcmds/tests/test_mathlib.cpp b/src/systemcmds/tests/test_mathlib.cpp index df3ddb966..70d173fc9 100644 --- a/src/systemcmds/tests/test_mathlib.cpp +++ b/src/systemcmds/tests/test_mathlib.cpp @@ -98,6 +98,8 @@ int test_mathlib(int argc, char *argv[]) TEST_OP("Vector<3> length squared", v1.length_squared()); #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wunused-variable" + // Need pragma here intead of moving variable out of TEST_OP and just reference because + // TEST_OP measures performance of vector operations. TEST_OP("Vector<3> element read", volatile float a = v1(0)); TEST_OP("Vector<3> element read direct", volatile float a = v1.data[0]); #pragma GCC diagnostic pop -- cgit v1.2.3 From 6f1292838960ca9eb72dc1818250eb50f70ddb98 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 7 Jul 2014 20:00:44 -0700 Subject: Fix mainStateTransitionTest --- .../commander_tests/state_machine_helper_test.cpp | 213 ++++++++++++++------- 1 file changed, 147 insertions(+), 66 deletions(-) diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp index ee0d08391..2e18c4284 100644 --- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp +++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp @@ -183,12 +183,12 @@ bool StateMachineHelperTest::armingStateTransitionTest(void) // Safety switch arming tests - { "transition: init to standby, no safety switch", + { "transition: standby to armed, no safety switch", { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_NOT_AVAILABLE, ATT_SAFETY_OFF, ARMING_STATE_ARMED, { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED }, - { "transition: init to standby, safety switch off", + { "transition: standby to armed, safety switch off", { ARMING_STATE_STANDBY, ATT_DISARMED, ATT_READY_TO_ARM }, HIL_STATE_OFF, ATT_SENSORS_INITIALIZED, ATT_SAFETY_AVAILABLE, ATT_SAFETY_OFF, ARMING_STATE_ARMED, { ARMING_STATE_ARMED, ATT_ARMED, ATT_READY_TO_ARM }, TRANSITION_CHANGED }, @@ -286,7 +286,7 @@ bool StateMachineHelperTest::armingStateTransitionTest(void) armed.ready_to_arm = test->current_state.ready_to_arm; // Attempt transition - transition_result_t result = arming_state_transition(&status, &safety, test->requested_state, &armed); + transition_result_t result = arming_state_transition(&status, &safety, test->requested_state, &armed, 0 /* no mavlink_fd */); // Validate result of transition ut_assert(test->assertMsg, test->expected_transition_result == result); @@ -300,70 +300,151 @@ bool StateMachineHelperTest::armingStateTransitionTest(void) bool StateMachineHelperTest::mainStateTransitionTest(void) { - struct vehicle_status_s current_state; - main_state_t new_main_state; + // This structure represent a single test case for testing Main State transitions. + typedef struct { + const char* assertMsg; // Text to show when test case fails + uint8_t condition_bits; // Bits for various condition_* values + main_state_t from_state; // State prior to transition request + main_state_t to_state; // State to transition to + transition_result_t expected_transition_result; // Expected result from main_state_transition call + } MainTransitionTest_t; + + // Bits for condition_bits + #define MTT_ALL_NOT_VALID 0 + #define MTT_ROTARY_WING 1 << 0 + #define MTT_LOC_ALT_VALID 1 << 1 + #define MTT_LOC_POS_VALID 1 << 2 + #define MTT_HOME_POS_VALID 1 << 3 + #define MTT_GLOBAL_POS_VALID 1 << 4 + + static const MainTransitionTest_t rgMainTransitionTests[] = { + + // TRANSITION_NOT_CHANGED tests + + { "no transition: identical states", + MTT_ALL_NOT_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_MANUAL, TRANSITION_NOT_CHANGED }, + + // TRANSITION_CHANGED tests + + { "transition: MANUAL to ACRO", + MTT_ALL_NOT_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_ACRO, TRANSITION_CHANGED }, + + { "transition: ACRO to MANUAL", + MTT_ALL_NOT_VALID, + MAIN_STATE_ACRO, MAIN_STATE_MANUAL, TRANSITION_CHANGED }, + + { "transition: MANUAL to AUTO_MISSION - global position valid", + MTT_GLOBAL_POS_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_AUTO_MISSION, TRANSITION_CHANGED }, + + { "transition: AUTO_MISSION to MANUAL - global position valid", + MTT_GLOBAL_POS_VALID, + MAIN_STATE_AUTO_MISSION, MAIN_STATE_MANUAL, TRANSITION_CHANGED }, + + { "transition: MANUAL to AUTO_LOITER - global position valid", + MTT_GLOBAL_POS_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_AUTO_LOITER, TRANSITION_CHANGED }, + + { "transition: AUTO_LOITER to MANUAL - global position valid", + MTT_GLOBAL_POS_VALID, + MAIN_STATE_AUTO_LOITER, MAIN_STATE_MANUAL, TRANSITION_CHANGED }, + + { "transition: MANUAL to AUTO_RTL - global position valid, home position valid", + MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_CHANGED }, + + { "transition: AUTO_RTL to MANUAL - global position valid, home position valid", + MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID, + MAIN_STATE_AUTO_RTL, MAIN_STATE_MANUAL, TRANSITION_CHANGED }, + + { "transition: MANUAL to ALTCTL - not rotary", + MTT_ALL_NOT_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_CHANGED }, + + { "transition: MANUAL to ALTCTL - rotary, global position not valid, local altitude valid", + MTT_ROTARY_WING | MTT_LOC_ALT_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_CHANGED }, + + { "transition: MANUAL to ALTCTL - rotary, global position valid, local altitude not valid", + MTT_ROTARY_WING | MTT_GLOBAL_POS_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_CHANGED }, + + { "transition: ALTCTL to MANUAL - local altitude valid", + MTT_LOC_ALT_VALID, + MAIN_STATE_ALTCTL, MAIN_STATE_MANUAL, TRANSITION_CHANGED }, + + { "transition: MANUAL to POSCTL - local position not valid, global position valid", + MTT_GLOBAL_POS_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_POSCTL, TRANSITION_CHANGED }, + + { "transition: MANUAL to POSCTL - local position valid, global position not valid", + MTT_LOC_POS_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_POSCTL, TRANSITION_CHANGED }, + + { "transition: POSCTL to MANUAL - local position valid, global position valid", + MTT_LOC_POS_VALID, + MAIN_STATE_POSCTL, MAIN_STATE_MANUAL, TRANSITION_CHANGED }, + + // TRANSITION_DENIED tests + + { "no transition: MANUAL to AUTO_MISSION - global position not valid", + MTT_ALL_NOT_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_AUTO_MISSION, TRANSITION_DENIED }, + + { "no transition: MANUAL to AUTO_LOITER - global position not valid", + MTT_ALL_NOT_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_AUTO_LOITER, TRANSITION_DENIED }, + + { "no transition: MANUAL to AUTO_RTL - global position not valid, home position not valid", + MTT_ALL_NOT_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_DENIED }, + + { "no transition: MANUAL to AUTO_RTL - global position not valid, home position valid", + MTT_HOME_POS_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_DENIED }, + + { "no transition: MANUAL to AUTO_RTL - global position valid, home position not valid", + MTT_GLOBAL_POS_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_AUTO_RTL, TRANSITION_DENIED }, + + { "no transition: MANUAL to ALTCTL - rotary, global position not valid, local altitude not valid", + MTT_ROTARY_WING, + MAIN_STATE_MANUAL, MAIN_STATE_ALTCTL, TRANSITION_DENIED }, + + { "no transition: MANUAL to POSCTL - local position not valid, global position not valid", + MTT_ALL_NOT_VALID, + MAIN_STATE_MANUAL, MAIN_STATE_POSCTL, TRANSITION_DENIED }, + }; - // Identical states. - current_state.main_state = MAIN_STATE_MANUAL; - new_main_state = MAIN_STATE_MANUAL; - ut_assert("no transition: identical states", - TRANSITION_NOT_CHANGED == main_state_transition(¤t_state, new_main_state)); - ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state); - - // AUTO to MANUAL. - current_state.main_state = MAIN_STATE_AUTO; - new_main_state = MAIN_STATE_MANUAL; - ut_assert("transition changed: auto to manual", - TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state)); - ut_assert("new state: manual", MAIN_STATE_MANUAL == current_state.main_state); - - // MANUAL to ALTCTRL. - current_state.main_state = MAIN_STATE_MANUAL; - current_state.condition_local_altitude_valid = true; - new_main_state = MAIN_STATE_ALTCTL; - ut_assert("tranisition: manual to altctrl", - TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state)); - ut_assert("new state: altctrl", MAIN_STATE_ALTCTL == current_state.main_state); - - // MANUAL to ALTCTRL, invalid local altitude. - current_state.main_state = MAIN_STATE_MANUAL; - current_state.condition_local_altitude_valid = false; - new_main_state = MAIN_STATE_ALTCTL; - ut_assert("no transition: invalid local altitude", - TRANSITION_DENIED == main_state_transition(¤t_state, new_main_state)); - ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state); - - // MANUAL to POSCTRL. - current_state.main_state = MAIN_STATE_MANUAL; - current_state.condition_local_position_valid = true; - new_main_state = MAIN_STATE_POSCTL; - ut_assert("transition: manual to posctrl", - TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state)); - ut_assert("current state: posctrl", MAIN_STATE_POSCTL == current_state.main_state); - - // MANUAL to POSCTRL, invalid local position. - current_state.main_state = MAIN_STATE_MANUAL; - current_state.condition_local_position_valid = false; - new_main_state = MAIN_STATE_POSCTL; - ut_assert("no transition: invalid position", - TRANSITION_DENIED == main_state_transition(¤t_state, new_main_state)); - ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state); - - // MANUAL to AUTO. - current_state.main_state = MAIN_STATE_MANUAL; - current_state.condition_global_position_valid = true; - new_main_state = MAIN_STATE_AUTO; - ut_assert("transition: manual to auto", - TRANSITION_CHANGED == main_state_transition(¤t_state, new_main_state)); - ut_assert("current state: auto", MAIN_STATE_AUTO == current_state.main_state); - - // MANUAL to AUTO, invalid global position. - current_state.main_state = MAIN_STATE_MANUAL; - current_state.condition_global_position_valid = false; - new_main_state = MAIN_STATE_AUTO; - ut_assert("no transition: invalid global position", - TRANSITION_DENIED == main_state_transition(¤t_state, new_main_state)); - ut_assert("current state: manual", MAIN_STATE_MANUAL == current_state.main_state); + size_t cMainTransitionTests = sizeof(rgMainTransitionTests) / sizeof(rgMainTransitionTests[0]); + for (size_t i=0; ifrom_state; + current_state.is_rotary_wing = test->condition_bits & MTT_ROTARY_WING; + current_state.condition_local_altitude_valid = test->condition_bits & MTT_LOC_ALT_VALID; + current_state.condition_local_position_valid = test->condition_bits & MTT_LOC_POS_VALID; + current_state.condition_home_position_valid = test->condition_bits & MTT_HOME_POS_VALID; + current_state.condition_global_position_valid = test->condition_bits & MTT_GLOBAL_POS_VALID; + + // Attempt transition + transition_result_t result = main_state_transition(¤t_state, test->to_state); + + // Validate result of transition + ut_assert(test->assertMsg, test->expected_transition_result == result); + if (test->expected_transition_result == result) { + if (test->expected_transition_result == TRANSITION_CHANGED) { + ut_assert(test->assertMsg, test->to_state == current_state.main_state); + } else { + ut_assert(test->assertMsg, test->from_state == current_state.main_state); + } + } + } + return true; } -- cgit v1.2.3 From c3826505ed36b4efa0272f863e45ea590b646e74 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 09:15:20 +0200 Subject: HIL: reduce excessive stack usage of driver --- src/drivers/hil/hil.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/hil/hil.cpp b/src/drivers/hil/hil.cpp index 55cc077fb..f17e99e9d 100644 --- a/src/drivers/hil/hil.cpp +++ b/src/drivers/hil/hil.cpp @@ -229,7 +229,7 @@ HIL::init() _task = task_spawn_cmd("fmuhil", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 2048, + 1200, (main_t)&HIL::task_main_trampoline, nullptr); -- cgit v1.2.3 From 3b448078878b3b16b0145bc9c1288ce278c0acc7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 09:15:47 +0200 Subject: Reduce excessive FMU stack usage --- src/drivers/px4fmu/fmu.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 0a4635728..d103935ae 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -329,7 +329,7 @@ PX4FMU::init() _task = task_spawn_cmd("fmuservo", SCHED_DEFAULT, SCHED_PRIORITY_DEFAULT, - 2048, + 1600, (main_t)&PX4FMU::task_main_trampoline, nullptr); -- cgit v1.2.3 From 41f4e5a6bc3859d3e7682fafe01ad8a075121127 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 09:57:08 +0200 Subject: ardrone interface: Remove unused variable --- src/drivers/ardrone_interface/ardrone_motor_control.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/drivers/ardrone_interface/ardrone_motor_control.c b/src/drivers/ardrone_interface/ardrone_motor_control.c index 81f634992..fc017dd58 100644 --- a/src/drivers/ardrone_interface/ardrone_motor_control.c +++ b/src/drivers/ardrone_interface/ardrone_motor_control.c @@ -382,8 +382,6 @@ void ardrone_mixing_and_output(int ardrone_write, const struct actuator_controls float output_band = 0.0f; const float startpoint_full_control = 0.25f; /**< start full control at 25% thrust */ - static bool initialized = false; - /* linearly scale the control inputs from 0 to startpoint_full_control */ if (motor_thrust < startpoint_full_control) { output_band = motor_thrust/startpoint_full_control; // linear from 0 to 1 -- cgit v1.2.3 From 0d0c4c36265b044ba978cfe4dbe369e93aa25d44 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 09:57:25 +0200 Subject: mc pos control: Fix reordering warnings --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 4e88e260c..9b0f69226 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -106,31 +106,31 @@ public: private: - bool _task_should_exit; /**< if true, task should exit */ + bool _task_should_exit; /**< if true, task should exit */ int _control_task; /**< task handle for task */ int _mavlink_fd; /**< mavlink fd */ int _att_sub; /**< vehicle attitude subscription */ int _att_sp_sub; /**< vehicle attitude setpoint */ int _control_mode_sub; /**< vehicle control mode subscription */ - int _params_sub; /**< notification of parameter updates */ - int _manual_sub; /**< notification of manual control updates */ + int _params_sub; /**< notification of parameter updates */ + int _manual_sub; /**< notification of manual control updates */ int _arming_sub; /**< arming status of outputs */ int _local_pos_sub; /**< vehicle local position */ int _pos_sp_triplet_sub; /**< position setpoint triplet */ - int _local_pos_sp_sub; /**< offboard local position setpoint */ - int _global_vel_sp_sub; /**< offboard global velocity setpoint */ + int _local_pos_sp_sub; /**< offboard local position setpoint */ + int _global_vel_sp_sub; /**< offboard global velocity setpoint */ orb_advert_t _att_sp_pub; /**< attitude setpoint publication */ orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */ orb_advert_t _global_vel_sp_pub; /**< vehicle global velocity setpoint publication */ struct vehicle_attitude_s _att; /**< vehicle attitude */ - struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */ - struct manual_control_setpoint_s _manual; /**< r/c channel data */ - struct vehicle_control_mode_s _control_mode; /**< vehicle control mode */ + struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */ + struct manual_control_setpoint_s _manual; /**< r/c channel data */ + struct vehicle_control_mode_s _control_mode; /**< vehicle control mode */ struct actuator_armed_s _arming; /**< actuator arming status */ - struct vehicle_local_position_s _local_pos; /**< vehicle local position */ + struct vehicle_local_position_s _local_pos; /**< vehicle local position */ struct position_setpoint_triplet_s _pos_sp_triplet; /**< vehicle global position setpoint triplet */ struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position setpoint */ struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */ @@ -258,8 +258,8 @@ MulticopterPositionControl::MulticopterPositionControl() : _manual_sub(-1), _arming_sub(-1), _local_pos_sub(-1), - _global_vel_sp_sub(-1), _pos_sp_triplet_sub(-1), + _global_vel_sp_sub(-1), /* publications */ _att_sp_pub(-1), -- cgit v1.2.3 From 9f1661f1f8808b7c83f73284cee9a1e9279165d3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 09:58:08 +0200 Subject: Silence FTP transactions, be vocal about errors --- src/modules/mavlink/mavlink_ftp.cpp | 19 ++++++++++--------- src/modules/mavlink/mavlink_ftp.h | 27 ++++++++++++++------------- src/modules/mavlink/mavlink_receiver.cpp | 2 +- 3 files changed, 25 insertions(+), 23 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index 57ae6076c..675a6870e 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -117,10 +117,10 @@ MavlinkFTP::_worker(Request *req) if (crc32(req->rawData(), req->dataSize()) != messageCRC) { errorCode = kErrNoRequest; goto out; - printf("ftp: bad crc\n"); + warnx("ftp: bad crc"); } - printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset); + //printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset); switch (hdr->opcode) { case kCmdNone: @@ -167,9 +167,9 @@ out: // handle success vs. error if (errorCode == kErrNone) { hdr->opcode = kRspAck; - printf("FTP: ack\n"); + //warnx("FTP: ack\n"); } else { - printf("FTP: nak %u\n", errorCode); + warnx("FTP: nak %u", errorCode); hdr->opcode = kRspNak; hdr->size = 1; hdr->data[0] = errorCode; @@ -206,11 +206,11 @@ MavlinkFTP::_workList(Request *req) DIR *dp = opendir(dirPath); if (dp == nullptr) { - printf("FTP: can't open path '%s'\n", dirPath); + warnx("FTP: can't open path '%s'", dirPath); return kErrNotDir; } - printf("FTP: list %s offset %d\n", dirPath, hdr->offset); + //warnx("FTP: list %s offset %d", dirPath, hdr->offset); ErrorCode errorCode = kErrNone; struct dirent entry, *result = nullptr; @@ -222,7 +222,7 @@ MavlinkFTP::_workList(Request *req) for (;;) { // read the directory entry if (readdir_r(dp, &entry, &result)) { - printf("FTP: list %s readdir_r failure\n", dirPath); + warnx("FTP: list %s readdir_r failure\n", dirPath); errorCode = kErrIO; break; } @@ -304,19 +304,20 @@ MavlinkFTP::_workRead(Request *req) } // Seek to the specified position - printf("Seek %d\n", hdr->offset); + //warnx("seek %d", hdr->offset); if (lseek(_session_fds[session_index], hdr->offset, SEEK_SET) < 0) { // Unable to see to the specified location + warnx("seek fail"); return kErrEOF; } int bytes_read = ::read(_session_fds[session_index], &hdr->data[0], kMaxDataLength); if (bytes_read < 0) { // Negative return indicates error other than eof + warnx("read fail %d", bytes_read); return kErrIO; } - printf("Read success %d\n", bytes_read); hdr->size = bytes_read; return kErrNone; diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h index e22e61553..59237a4c4 100644 --- a/src/modules/mavlink/mavlink_ftp.h +++ b/src/modules/mavlink/mavlink_ftp.h @@ -147,20 +147,21 @@ private: unsigned len = mavlink_msg_encapsulated_data_pack_chan(_mavlink->get_system_id(), _mavlink->get_component_id(), _mavlink->get_channel(), &msg, sequence(), rawData()); - _mavlink->lockMessageBufferMutex(); - bool fError = _mavlink->message_buffer_write(&msg, len); - _mavlink->unlockMessageBufferMutex(); - - if (!fError) { + _mavlink->lockMessageBufferMutex(); + bool success = _mavlink->message_buffer_write(&msg, len); + _mavlink->unlockMessageBufferMutex(); + + if (!success) { warnx("FTP TX ERR"); - } else { - warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d", - _mavlink->get_system_id(), - _mavlink->get_component_id(), - _mavlink->get_channel(), - len, - msg.checksum); - } + } + // else { + // warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d", + // _mavlink->get_system_id(), + // _mavlink->get_component_id(), + // _mavlink->get_channel(), + // len, + // msg.checksum); + // } } uint8_t *rawData() { return &_message.data[0]; } diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 81966caf8..484886682 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -442,7 +442,7 @@ MavlinkReceiver::handle_message_manual_control(mavlink_message_t *msg) manual.r = man.r / 1000.0f; manual.z = man.z / 1000.0f; - warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", manual.x, manual.y, manual.r, manual.z); + warnx("pitch: %.2f, roll: %.2f, yaw: %.2f, throttle: %.2f", (double)manual.x, (double)manual.y, (double)manual.r, (double)manual.z); if (_manual_pub < 0) { _manual_pub = orb_advertise(ORB_ID(manual_control_setpoint), &manual); -- cgit v1.2.3 From 86932423af88f9ed0a53e0fab6b12160ff0b3efb Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 8 Jul 2014 10:50:59 +0200 Subject: update mavlink to latest master --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 45a71d656..3711190d2 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 45a71d6564bc5c47ed97d620089e17ca48bab73f +Subproject commit 3711190d23d9928ea0687e00621c8d9ecf145f50 -- cgit v1.2.3 From 37b4cdfce21ff6a7374599a6706ad387bd359515 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 25 Mar 2014 10:56:33 +1100 Subject: board_serial: use a uint8_t buffer we should not be using 'char' for binary APIs, as the C standard does not specify if it is signed or unsigned, so results may not be consistent --- src/drivers/px4fmu/fmu.cpp | 2 +- src/modules/systemlib/board_serial.c | 8 ++++---- src/modules/systemlib/board_serial.h | 2 +- src/modules/systemlib/otp.h | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 0a4635728..39cc32967 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -1784,7 +1784,7 @@ fmu_main(int argc, char *argv[]) } if (!strcmp(verb, "id")) { - char id[12]; + uint8_t id[12]; (void)get_board_serial(id); errx(0, "Board serial:\n %02X%02X%02X%02X %02X%02X%02X%02X %02X%02X%02X%02X", diff --git a/src/modules/systemlib/board_serial.c b/src/modules/systemlib/board_serial.c index ad8c2bf83..182fd15c6 100644 --- a/src/modules/systemlib/board_serial.c +++ b/src/modules/systemlib/board_serial.c @@ -44,11 +44,11 @@ #include "board_config.h" #include "board_serial.h" -int get_board_serial(char *serialid) +int get_board_serial(uint8_t *serialid) { - const volatile unsigned *udid_ptr = (const unsigned *)UDID_START; + const volatile uint32_t *udid_ptr = (const uint32_t *)UDID_START; union udid id; - val_read((unsigned *)&id, udid_ptr, sizeof(id)); + val_read((uint32_t *)&id, udid_ptr, sizeof(id)); /* Copy the serial from the chips non-write memory and swap endianess */ @@ -57,4 +57,4 @@ int get_board_serial(char *serialid) serialid[8] = id.data[11]; serialid[9] = id.data[10]; serialid[10] = id.data[9]; serialid[11] = id.data[8]; return 0; -} \ No newline at end of file +} diff --git a/src/modules/systemlib/board_serial.h b/src/modules/systemlib/board_serial.h index b14bb4376..873d9657b 100644 --- a/src/modules/systemlib/board_serial.h +++ b/src/modules/systemlib/board_serial.h @@ -44,6 +44,6 @@ __BEGIN_DECLS -__EXPORT int get_board_serial(char *serialid); +__EXPORT int get_board_serial(uint8_t *serialid); __END_DECLS diff --git a/src/modules/systemlib/otp.h b/src/modules/systemlib/otp.h index f10e129d8..273b064f0 100644 --- a/src/modules/systemlib/otp.h +++ b/src/modules/systemlib/otp.h @@ -125,7 +125,7 @@ struct otp_lock { #pragma pack(push, 1) union udid { uint32_t serial[3]; - char data[12]; + uint8_t data[12]; }; #pragma pack(pop) -- cgit v1.2.3 From ef79d032760e83850a9dbcbe5ae34c8b72f5fb4f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 14 May 2014 16:01:10 +1000 Subject: mpu6000: allow disabling of on-sensor low pass filter used for vibration testing --- src/drivers/mpu6000/mpu6000.cpp | 20 +++++++++++++------- 1 file changed, 13 insertions(+), 7 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 0edec3d0e..fb4acc360 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -666,7 +666,9 @@ MPU6000::_set_dlpf_filter(uint16_t frequency_hz) /* choose next highest filter frequency available */ - if (frequency_hz <= 5) { + if (frequency_hz == 0) { + filter = BITS_DLPF_CFG_2100HZ_NOLPF; + } else if (frequency_hz <= 5) { filter = BITS_DLPF_CFG_5HZ; } else if (frequency_hz <= 10) { filter = BITS_DLPF_CFG_10HZ; @@ -922,10 +924,11 @@ MPU6000::ioctl(struct file *filp, int cmd, unsigned long arg) return _accel_filter_x.get_cutoff_freq(); case ACCELIOCSLOWPASS: - - // XXX decide on relationship of both filters - // i.e. disable the on-chip filter - //_set_dlpf_filter((uint16_t)arg); + if (arg == 0) { + // allow disabling of on-chip filter using + // zero as desired filter frequency + _set_dlpf_filter(0); + } _accel_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg); _accel_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg); _accel_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg); @@ -1009,8 +1012,11 @@ MPU6000::gyro_ioctl(struct file *filp, int cmd, unsigned long arg) _gyro_filter_x.set_cutoff_frequency(1.0e6f / _call_interval, arg); _gyro_filter_y.set_cutoff_frequency(1.0e6f / _call_interval, arg); _gyro_filter_z.set_cutoff_frequency(1.0e6f / _call_interval, arg); - // XXX check relation to the internal lowpass - //_set_dlpf_filter((uint16_t)arg); + if (arg == 0) { + // allow disabling of on-chip filter using 0 + // as desired frequency + _set_dlpf_filter(0); + } return OK; case GYROIOCSSCALE: -- cgit v1.2.3 From 07855120268cef79e9d23d7cd091c526fa4622af Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 19 May 2014 16:49:41 +1000 Subject: px_uploader: added ModemManager warning --- Tools/px_uploader.py | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index 985e6ffd9..a113f5628 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -63,6 +63,7 @@ import zlib import base64 import time import array +import os from sys import platform as _platform @@ -449,6 +450,12 @@ parser.add_argument('--baud', action="store", type=int, default=115200, help="Ba parser.add_argument('firmware', action="store", help="Firmware file to be uploaded") args = parser.parse_args() +# warn people about ModemManager which interferes badly with Pixhawk +if os.path.exists("/usr/sbin/ModemManager"): + print("=======================================================================") + print("WARNING: You should uninstall ModemManager as it conflicts with Pixhawk") + print("=======================================================================") + # Load the firmware file fw = firmware(args.firmware) print("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision'))) -- cgit v1.2.3 From d6999384ceb905f82896b99dda6341c7b615ba7c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 11:42:46 +0200 Subject: Improve modem manager warning to avoid having smart people tell us we have Linux compatibility issues while we actually do not. --- Tools/px_uploader.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Tools/px_uploader.py b/Tools/px_uploader.py index a113f5628..cd7884f6d 100755 --- a/Tools/px_uploader.py +++ b/Tools/px_uploader.py @@ -452,9 +452,9 @@ args = parser.parse_args() # warn people about ModemManager which interferes badly with Pixhawk if os.path.exists("/usr/sbin/ModemManager"): - print("=======================================================================") - print("WARNING: You should uninstall ModemManager as it conflicts with Pixhawk") - print("=======================================================================") + print("==========================================================================================================") + print("WARNING: You should uninstall ModemManager as it conflicts with any non-modem serial device (like Pixhawk)") + print("==========================================================================================================") # Load the firmware file fw = firmware(args.firmware) -- cgit v1.2.3 From db304480d996c134fbc2525e5bc96a08178275a9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 20 May 2014 11:14:38 +1000 Subject: lsm303d: disable check_extremes code this could trigger with a bungee launch, and could cause higher latency due to SD card writes --- src/drivers/lsm303d/lsm303d.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 8bf76dcc3..56baf3274 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -75,6 +75,10 @@ #endif static const int ERROR = -1; +// enable this to debug the buggy lsm303d sensor in very early +// prototype pixhawk boards +#define CHECK_EXTREMES 0 + /* SPI protocol address bits */ #define DIR_READ (1<<7) #define DIR_WRITE (0<<7) @@ -830,7 +834,9 @@ LSM303D::read(struct file *filp, char *buffer, size_t buflen) */ while (count--) { if (_accel_reports->get(arb)) { +#if CHECK_EXTREMES check_extremes(arb); +#endif ret += sizeof(*arb); arb++; } -- cgit v1.2.3 From 644d4bb3dc6186d7908ed0aa75d973cfc0826253 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Jun 2014 10:06:52 +1000 Subject: FMUv2: added defines for FMUv3 sensors this enables EXT0 to EXT3 on external SPI bus, and gives correct names for FMUv3 board --- src/drivers/boards/px4fmu-v2/board_config.h | 10 ++++++++++ src/drivers/boards/px4fmu-v2/px4fmu_spi.c | 24 ++++++++++++++++++++++++ 2 files changed, 34 insertions(+) diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h index 36eb7bec4..2ed51d7b1 100644 --- a/src/drivers/boards/px4fmu-v2/board_config.h +++ b/src/drivers/boards/px4fmu-v2/board_config.h @@ -108,6 +108,8 @@ __BEGIN_DECLS #define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN2) #define GPIO_SPI_CS_EXT0 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4) #define GPIO_SPI_CS_EXT1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14) +#define GPIO_SPI_CS_EXT2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15) +#define GPIO_SPI_CS_EXT3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN13) #define PX4_SPI_BUS_SENSORS 1 #define PX4_SPI_BUS_EXT 4 @@ -121,6 +123,14 @@ __BEGIN_DECLS /* External bus */ #define PX4_SPIDEV_EXT0 1 #define PX4_SPIDEV_EXT1 2 +#define PX4_SPIDEV_EXT2 3 +#define PX4_SPIDEV_EXT3 4 + +/* FMUv3 SPI on external bus */ +#define PX4_SPIDEV_EXT_MPU PX4_SPIDEV_EXT0 +#define PX4_SPIDEV_EXT_BARO PX4_SPIDEV_EXT1 +#define PX4_SPIDEV_EXT_ACCEL_MAG PX4_SPIDEV_EXT2 +#define PX4_SPIDEV_EXT_GYRO PX4_SPIDEV_EXT3 /* I2C busses */ #define PX4_I2C_BUS_EXPANSION 1 diff --git a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c index 01dbd6e77..8c37d31a7 100644 --- a/src/drivers/boards/px4fmu-v2/px4fmu_spi.c +++ b/src/drivers/boards/px4fmu-v2/px4fmu_spi.c @@ -98,8 +98,12 @@ __EXPORT void weak_function stm32_spiinitialize(void) #ifdef CONFIG_STM32_SPI4 stm32_configgpio(GPIO_SPI_CS_EXT0); stm32_configgpio(GPIO_SPI_CS_EXT1); + stm32_configgpio(GPIO_SPI_CS_EXT2); + stm32_configgpio(GPIO_SPI_CS_EXT3); stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1); stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1); #endif } @@ -174,12 +178,32 @@ __EXPORT void stm32_spi4select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, /* Making sure the other peripherals are not selected */ stm32_gpiowrite(GPIO_SPI_CS_EXT0, !selected); stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1); break; case PX4_SPIDEV_EXT1: /* Making sure the other peripherals are not selected */ + stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1); stm32_gpiowrite(GPIO_SPI_CS_EXT1, !selected); + stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1); + break; + + case PX4_SPIDEV_EXT2: + /* Making sure the other peripherals are not selected */ + stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT2, !selected); + stm32_gpiowrite(GPIO_SPI_CS_EXT3, 1); + break; + + case PX4_SPIDEV_EXT3: + /* Making sure the other peripherals are not selected */ stm32_gpiowrite(GPIO_SPI_CS_EXT0, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT1, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT2, 1); + stm32_gpiowrite(GPIO_SPI_CS_EXT3, !selected); break; default: -- cgit v1.2.3 From fea4845ed97ca5219ceb8af0b0fb6d68603eea17 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Jun 2014 12:13:05 +1000 Subject: SPI: make _bus protected this allows runtime use of internal/external bus to determine if DRDY should be used on the L3GD20 --- src/drivers/device/spi.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h index 299575dc5..03986da1e 100644 --- a/src/drivers/device/spi.h +++ b/src/drivers/device/spi.h @@ -124,11 +124,13 @@ protected: LockMode locking_mode; /**< selected locking mode */ private: - int _bus; enum spi_dev_e _device; enum spi_mode_e _mode; uint32_t _frequency; struct spi_dev_s *_dev; + +protected: + int _bus; }; } // namespace device -- cgit v1.2.3 From e7360f40169a0d467448bca8f85d32a84025ca4e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Jun 2014 12:13:58 +1000 Subject: l3gd20: added -X switch for external bus --- src/drivers/l3gd20/l3gd20.cpp | 50 ++++++++++++++++++++++++++++++++++++------- 1 file changed, 42 insertions(+), 8 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 37e72388b..06b36d688 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -54,6 +54,7 @@ #include #include #include +#include #include #include @@ -821,7 +822,7 @@ L3GD20::measure() // if the gyro doesn't have any data ready then re-schedule // for 100 microseconds later. This ensures we don't double // read a value and then miss the next value - if (stm32_gpioread(GPIO_EXTI_GYRO_DRDY) == 0) { + if (_bus == PX4_SPI_BUS_SENSORS && stm32_gpioread(GPIO_EXTI_GYRO_DRDY) == 0) { perf_count(_reschedules); hrt_call_delay(&_call, 100); return; @@ -983,7 +984,7 @@ void info(); * Start the driver. */ void -start() +start(bool external_bus) { int fd; @@ -991,7 +992,15 @@ start() errx(0, "already started"); /* create the driver */ - g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO); + if (external_bus) { +#ifdef PX4_SPI_BUS_EXT + g_dev = new L3GD20(PX4_SPI_BUS_EXT, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_EXT_GYRO); +#else + errx(0, "External SPI not available"); +#endif + } else { + g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO); + } if (g_dev == nullptr) goto fail; @@ -1106,32 +1115,57 @@ info() } // namespace +void +l3gd20_usage() +{ + warnx("missing command: try 'start', 'info', 'test', 'reset'"); + warnx("options:"); + warnx(" -X (external bus)"); +} + int l3gd20_main(int argc, char *argv[]) { + bool external_bus = false; + int ch; + + /* jump over start/off/etc and look at options first */ + while ((ch = getopt(argc, argv, "X")) != EOF) { + switch (ch) { + case 'X': + external_bus = true; + break; + default: + l3gd20_usage(); + exit(0); + } + } + + const char *verb = argv[optind]; + /* * Start/load the driver. */ - if (!strcmp(argv[1], "start")) - l3gd20::start(); + if (!strcmp(verb, "start")) + l3gd20::start(external_bus); /* * Test the driver/device. */ - if (!strcmp(argv[1], "test")) + if (!strcmp(verb, "test")) l3gd20::test(); /* * Reset the driver. */ - if (!strcmp(argv[1], "reset")) + if (!strcmp(verb, "reset")) l3gd20::reset(); /* * Print driver information. */ - if (!strcmp(argv[1], "info")) + if (!strcmp(verb, "info")) l3gd20::info(); errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'"); -- cgit v1.2.3 From e0dbc82d84c2ad0e36b88f6b6d3cbfab866b4c44 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Jun 2014 12:14:17 +1000 Subject: lsm303d: added -X option for external bus --- src/drivers/lsm303d/lsm303d.cpp | 51 ++++++++++++++++++++++++++++++++--------- 1 file changed, 40 insertions(+), 11 deletions(-) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 56baf3274..0428901a3 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -52,6 +52,7 @@ #include #include #include +#include #include #include @@ -85,6 +86,7 @@ static const int ERROR = -1; #define ADDR_INCREMENT (1<<6) #define LSM303D_DEVICE_PATH_ACCEL "/dev/lsm303d_accel" +#define LSM303D_DEVICE_PATH_ACCEL_EXT "/dev/lsm303d_accel_ext" #define LSM303D_DEVICE_PATH_MAG "/dev/lsm303d_mag" /* register addresses: A: accel, M: mag, T: temp */ @@ -1791,16 +1793,18 @@ void logging(); * Start the driver. */ void -start() +start(bool external_bus) { int fd, fd_mag; - if (g_dev != nullptr) errx(0, "already started"); /* create the driver */ - g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG); - + if (external_bus) { + g_dev = new LSM303D(PX4_SPI_BUS_EXT, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_EXT_ACCEL_MAG); + } else { + g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG); + } if (g_dev == nullptr) { warnx("failed instantiating LSM303D obj"); goto fail; @@ -1998,44 +2002,69 @@ logging() } // namespace +void +lsm303d_usage() +{ + warnx("missing command: try 'start', 'info', 'test', 'reset', 'regdump', 'logging'"); + warnx("options:"); + warnx(" -X (external bus)"); +} + int lsm303d_main(int argc, char *argv[]) { + bool external_bus = false; + int ch; + + /* jump over start/off/etc and look at options first */ + while ((ch = getopt(argc, argv, "X")) != EOF) { + switch (ch) { + case 'X': + external_bus = true; + break; + default: + lsm303d_usage(); + exit(0); + } + } + + const char *verb = argv[optind]; + /* * Start/load the driver. */ - if (!strcmp(argv[1], "start")) - lsm303d::start(); + if (!strcmp(verb, "start")) + lsm303d::start(external_bus); /* * Test the driver/device. */ - if (!strcmp(argv[1], "test")) + if (!strcmp(verb, "test")) lsm303d::test(); /* * Reset the driver. */ - if (!strcmp(argv[1], "reset")) + if (!strcmp(verb, "reset")) lsm303d::reset(); /* * Print driver information. */ - if (!strcmp(argv[1], "info")) + if (!strcmp(verb, "info")) lsm303d::info(); /* * dump device registers */ - if (!strcmp(argv[1], "regdump")) + if (!strcmp(verb, "regdump")) lsm303d::regdump(); /* * dump device registers */ - if (!strcmp(argv[1], "logging")) + if (!strcmp(verb, "logging")) lsm303d::logging(); errx(1, "unrecognized command, try 'start', 'test', 'reset', 'info', 'logging' or 'regdump'"); -- cgit v1.2.3 From 541dc1825cfca3724a7fbe08abfdf88b881b0d3a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Jun 2014 12:14:33 +1000 Subject: mpu6000: added -X option for external bus --- src/drivers/mpu6000/mpu6000.cpp | 48 +++++++++++++++++++++++++++++++++++------ 1 file changed, 41 insertions(+), 7 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index fb4acc360..a1c169ffc 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -55,6 +55,7 @@ #include #include #include +#include #include #include @@ -1424,7 +1425,7 @@ void info(); * Start the driver. */ void -start() +start(bool external_bus) { int fd; @@ -1433,7 +1434,15 @@ start() errx(0, "already started"); /* create the driver */ - g_dev = new MPU6000(1 /* XXX magic number */, (spi_dev_e)PX4_SPIDEV_MPU); + if (external_bus) { +#ifdef PX4_SPI_BUS_EXT + g_dev = new MPU6000(PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU); +#else + errx(0, "External SPI not available"); +#endif + } else { + g_dev = new MPU6000(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU); + } if (g_dev == nullptr) goto fail; @@ -1578,32 +1587,57 @@ info() } // namespace +void +mpu6000_usage() +{ + warnx("missing command: try 'start', 'info', 'test', 'reset'"); + warnx("options:"); + warnx(" -X (external bus)"); +} + int mpu6000_main(int argc, char *argv[]) { + bool external_bus = false; + int ch; + + /* jump over start/off/etc and look at options first */ + while ((ch = getopt(argc, argv, "X")) != EOF) { + switch (ch) { + case 'X': + external_bus = true; + break; + default: + mpu6000_usage(); + exit(0); + } + } + + const char *verb = argv[optind]; + /* * Start/load the driver. */ - if (!strcmp(argv[1], "start")) - mpu6000::start(); + if (!strcmp(verb, "start")) + mpu6000::start(external_bus); /* * Test the driver/device. */ - if (!strcmp(argv[1], "test")) + if (!strcmp(verb, "test")) mpu6000::test(); /* * Reset the driver. */ - if (!strcmp(argv[1], "reset")) + if (!strcmp(verb, "reset")) mpu6000::reset(); /* * Print driver information. */ - if (!strcmp(argv[1], "info")) + if (!strcmp(verb, "info")) mpu6000::info(); errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'"); -- cgit v1.2.3 From ab90fe783287a068ee3654e488ea9144077586ab Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Jun 2014 12:15:43 +1000 Subject: ms5611: added -X option for external SPI bus --- src/drivers/ms5611/ms5611.cpp | 46 ++++++++++++++++++++++++++++++--------- src/drivers/ms5611/ms5611.h | 2 +- src/drivers/ms5611/ms5611_spi.cpp | 10 ++++++--- 3 files changed, 44 insertions(+), 14 deletions(-) diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp index 1ce93aeea..7a8d2eecf 100644 --- a/src/drivers/ms5611/ms5611.cpp +++ b/src/drivers/ms5611/ms5611.cpp @@ -50,6 +50,7 @@ #include #include #include +#include #include #include @@ -775,7 +776,7 @@ namespace ms5611 MS5611 *g_dev; -void start(); +void start(bool external_bus); void test(); void reset(); void info(); @@ -832,7 +833,7 @@ crc4(uint16_t *n_prom) * Start the driver. */ void -start() +start(bool external_bus) { int fd; prom_u prom_buf; @@ -845,7 +846,7 @@ start() /* create the driver, try SPI first, fall back to I2C if unsuccessful */ if (MS5611_spi_interface != nullptr) - interface = MS5611_spi_interface(prom_buf); + interface = MS5611_spi_interface(prom_buf, external_bus); if (interface == nullptr && (MS5611_i2c_interface != nullptr)) interface = MS5611_i2c_interface(prom_buf); @@ -1058,41 +1059,66 @@ calibrate(unsigned altitude) } // namespace +void +ms5611_usage() +{ + warnx("missing command: try 'start', 'info', 'test', 'test2', 'reset', 'calibrate'"); + warnx("options:"); + warnx(" -X (external bus)"); +} + int ms5611_main(int argc, char *argv[]) { + bool external_bus = false; + int ch; + + /* jump over start/off/etc and look at options first */ + while ((ch = getopt(argc, argv, "X")) != EOF) { + switch (ch) { + case 'X': + external_bus = true; + break; + default: + ms5611_usage(); + exit(0); + } + } + + const char *verb = argv[optind]; + /* * Start/load the driver. */ - if (!strcmp(argv[1], "start")) - ms5611::start(); + if (!strcmp(verb, "start")) + ms5611::start(external_bus); /* * Test the driver/device. */ - if (!strcmp(argv[1], "test")) + if (!strcmp(verb, "test")) ms5611::test(); /* * Reset the driver. */ - if (!strcmp(argv[1], "reset")) + if (!strcmp(verb, "reset")) ms5611::reset(); /* * Print driver information. */ - if (!strcmp(argv[1], "info")) + if (!strcmp(verb, "info")) ms5611::info(); /* * Perform MSL pressure calibration given an altitude in metres */ - if (!strcmp(argv[1], "calibrate")) { + if (!strcmp(verb, "calibrate")) { if (argc < 2) errx(1, "missing altitude"); - long altitude = strtol(argv[2], nullptr, 10); + long altitude = strtol(argv[optind+1], nullptr, 10); ms5611::calibrate(altitude); } diff --git a/src/drivers/ms5611/ms5611.h b/src/drivers/ms5611/ms5611.h index 76fb84de8..f0b3fd61d 100644 --- a/src/drivers/ms5611/ms5611.h +++ b/src/drivers/ms5611/ms5611.h @@ -80,6 +80,6 @@ extern bool crc4(uint16_t *n_prom); } /* namespace */ /* interface factories */ -extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf) weak_function; +extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus) weak_function; extern device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf) weak_function; diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp index 8759d16a1..00d016aed 100644 --- a/src/drivers/ms5611/ms5611_spi.cpp +++ b/src/drivers/ms5611/ms5611_spi.cpp @@ -62,7 +62,7 @@ #ifdef PX4_SPIDEV_BARO -device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf); +device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus); class MS5611_SPI : public device::SPI { @@ -115,9 +115,13 @@ private: }; device::Device * -MS5611_spi_interface(ms5611::prom_u &prom_buf) +MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus) { - return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf); + if (external_bus) { + return new MS5611_SPI(PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_BARO, prom_buf); + } else { + return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf); + } } MS5611_SPI::MS5611_SPI(int bus, spi_dev_e device, ms5611::prom_u &prom_buf) : -- cgit v1.2.3 From 19dbbf17e8b2fd37e43aa1a5cb6ae8c39012ab0f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 26 Jun 2014 13:51:04 +1000 Subject: mpu6000: allow for two mpu6000 instances, one internal, one external split g_dev into g_dev_int and g_dev_ext --- src/drivers/mpu6000/mpu6000.cpp | 82 +++++++++++++++++++++++------------------ 1 file changed, 46 insertions(+), 36 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index a1c169ffc..7f9e9fde4 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -78,6 +78,8 @@ #define MPU_DEVICE_PATH_ACCEL "/dev/mpu6000_accel" #define MPU_DEVICE_PATH_GYRO "/dev/mpu6000_gyro" +#define MPU_DEVICE_PATH_ACCEL_EXT "/dev/mpu6000_accel_ext" +#define MPU_DEVICE_PATH_GYRO_EXT "/dev/mpu6000_gyro_ext" // MPU 6000 registers #define MPUREG_WHOAMI 0x75 @@ -178,7 +180,7 @@ class MPU6000_gyro; class MPU6000 : public device::SPI { public: - MPU6000(int bus, spi_dev_e device); + MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device); virtual ~MPU6000(); virtual int init(); @@ -346,7 +348,7 @@ private: class MPU6000_gyro : public device::CDev { public: - MPU6000_gyro(MPU6000 *parent); + MPU6000_gyro(MPU6000 *parent, const char *path); ~MPU6000_gyro(); virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); @@ -369,9 +371,9 @@ private: /** driver 'main' command */ extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); } -MPU6000::MPU6000(int bus, spi_dev_e device) : - SPI("MPU6000", MPU_DEVICE_PATH_ACCEL, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED), - _gyro(new MPU6000_gyro(this)), +MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device) : + SPI("MPU6000", path_accel, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED), + _gyro(new MPU6000_gyro(this, path_gyro)), _product(0), _call_interval(0), _accel_reports(nullptr), @@ -1357,8 +1359,8 @@ MPU6000::print_info() _gyro_reports->print_info("gyro queue"); } -MPU6000_gyro::MPU6000_gyro(MPU6000 *parent) : - CDev("MPU6000_gyro", MPU_DEVICE_PATH_GYRO), +MPU6000_gyro::MPU6000_gyro(MPU6000 *parent, const char *path) : + CDev("MPU6000_gyro", path), _parent(parent), _gyro_topic(-1), _gyro_class_instance(-1) @@ -1414,12 +1416,13 @@ MPU6000_gyro::ioctl(struct file *filp, int cmd, unsigned long arg) namespace mpu6000 { -MPU6000 *g_dev; +MPU6000 *g_dev_int; // on internal bus +MPU6000 *g_dev_ext; // on external bus -void start(); -void test(); -void reset(); -void info(); +void start(bool); +void test(bool); +void reset(bool); +void info(bool); /** * Start the driver. @@ -1428,30 +1431,33 @@ void start(bool external_bus) { int fd; + MPU6000 **g_dev_ptr = external_bus?&g_dev_int:&g_dev_ext; + const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL; + const char *path_gyro = external_bus?MPU_DEVICE_PATH_GYRO_EXT:MPU_DEVICE_PATH_GYRO; - if (g_dev != nullptr) + if (*g_dev_ptr != nullptr) /* if already started, the still command succeeded */ errx(0, "already started"); /* create the driver */ if (external_bus) { #ifdef PX4_SPI_BUS_EXT - g_dev = new MPU6000(PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_MPU); + *g_dev_ptr = new MPU6000(PX4_SPI_BUS_EXT, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_EXT_MPU); #else errx(0, "External SPI not available"); #endif } else { - g_dev = new MPU6000(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_MPU); + *g_dev_ptr = new MPU6000(PX4_SPI_BUS_SENSORS, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_MPU); } - if (g_dev == nullptr) + if (*g_dev_ptr == nullptr) goto fail; - if (OK != g_dev->init()) + if (OK != (*g_dev_ptr)->init()) goto fail; /* set the poll rate to default, starts automatic data collection */ - fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY); + fd = open(path_accel, O_RDONLY); if (fd < 0) goto fail; @@ -1464,9 +1470,9 @@ start(bool external_bus) exit(0); fail: - if (g_dev != nullptr) { - delete g_dev; - g_dev = nullptr; + if (*g_dev_ptr != nullptr) { + delete (*g_dev_ptr); + *g_dev_ptr = nullptr; } errx(1, "driver start failed"); @@ -1478,24 +1484,26 @@ fail: * and automatic modes. */ void -test() +test(bool external_bus) { + const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL; + const char *path_gyro = external_bus?MPU_DEVICE_PATH_GYRO_EXT:MPU_DEVICE_PATH_GYRO; accel_report a_report; gyro_report g_report; ssize_t sz; /* get the driver */ - int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY); + int fd = open(path_accel, O_RDONLY); if (fd < 0) err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)", - MPU_DEVICE_PATH_ACCEL); + path_accel); /* get the driver */ - int fd_gyro = open(MPU_DEVICE_PATH_GYRO, O_RDONLY); + int fd_gyro = open(path_gyro, O_RDONLY); if (fd_gyro < 0) - err(1, "%s open failed", MPU_DEVICE_PATH_GYRO); + err(1, "%s open failed", path_gyro); /* reset to manual polling */ if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_MANUAL) < 0) @@ -1543,7 +1551,7 @@ test() /* XXX add poll-rate tests here too */ - reset(); + reset(external_bus); errx(0, "PASS"); } @@ -1551,9 +1559,10 @@ test() * Reset the driver. */ void -reset() +reset(bool external_bus) { - int fd = open(MPU_DEVICE_PATH_ACCEL, O_RDONLY); + const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL; + int fd = open(path_accel, O_RDONLY); if (fd < 0) err(1, "failed "); @@ -1573,13 +1582,14 @@ reset() * Print a little info about the driver. */ void -info() +info(bool external_bus) { - if (g_dev == nullptr) + MPU6000 **g_dev_ptr = external_bus?&g_dev_int:&g_dev_ext; + if (*g_dev_ptr == nullptr) errx(1, "driver not running"); - printf("state @ %p\n", g_dev); - g_dev->print_info(); + printf("state @ %p\n", *g_dev_ptr); + (*g_dev_ptr)->print_info(); exit(0); } @@ -1626,19 +1636,19 @@ mpu6000_main(int argc, char *argv[]) * Test the driver/device. */ if (!strcmp(verb, "test")) - mpu6000::test(); + mpu6000::test(external_bus); /* * Reset the driver. */ if (!strcmp(verb, "reset")) - mpu6000::reset(); + mpu6000::reset(external_bus); /* * Print driver information. */ if (!strcmp(verb, "info")) - mpu6000::info(); + mpu6000::info(external_bus); errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'"); } -- cgit v1.2.3 From e4e152a85b5a29cada6559197580a9dce93e45e3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 3 Jul 2014 11:30:05 +1000 Subject: FMUv2: added define for PX4_I2C_BUS_ONBOARD needed for hmc5883 on main bus (for FMUv3) --- src/drivers/boards/px4fmu-v2/board_config.h | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h index 2ed51d7b1..0190a5b5b 100644 --- a/src/drivers/boards/px4fmu-v2/board_config.h +++ b/src/drivers/boards/px4fmu-v2/board_config.h @@ -134,7 +134,8 @@ __BEGIN_DECLS /* I2C busses */ #define PX4_I2C_BUS_EXPANSION 1 -#define PX4_I2C_BUS_LED 2 +#define PX4_I2C_BUS_ONBOARD 2 +#define PX4_I2C_BUS_LED PX4_I2C_BUS_ONBOARD /* Devices on the onboard bus. * -- cgit v1.2.3 From f56724f7dff1f6d1167f4fd61015ffe24a64c8c9 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 3 Jul 2014 14:02:05 +1000 Subject: lib/conversion: added rotate_3f() will be used for user specified rotations in sensor drivers --- src/lib/conversion/rotation.cpp | 142 ++++++++++++++++++++++++++++++++++++++++ src/lib/conversion/rotation.h | 8 +++ 2 files changed, 150 insertions(+) diff --git a/src/lib/conversion/rotation.cpp b/src/lib/conversion/rotation.cpp index 614877b18..e17715733 100644 --- a/src/lib/conversion/rotation.cpp +++ b/src/lib/conversion/rotation.cpp @@ -49,3 +49,145 @@ get_rot_matrix(enum Rotation rot, math::Matrix<3,3> *rot_matrix) rot_matrix->from_euler(roll, pitch, yaw); } + +#define HALF_SQRT_2 0.70710678118654757f + +__EXPORT void +rotate_3f(enum Rotation rot, float &x, float &y, float &z) +{ + float tmp; + switch (rot) { + case ROTATION_NONE: + case ROTATION_MAX: + return; + case ROTATION_YAW_45: { + tmp = HALF_SQRT_2*(x - y); + y = HALF_SQRT_2*(x + y); + x = tmp; + return; + } + case ROTATION_YAW_90: { + tmp = x; x = -y; y = tmp; + return; + } + case ROTATION_YAW_135: { + tmp = -HALF_SQRT_2*(x + y); + y = HALF_SQRT_2*(x - y); + x = tmp; + return; + } + case ROTATION_YAW_180: + x = -x; y = -y; + return; + case ROTATION_YAW_225: { + tmp = HALF_SQRT_2*(y - x); + y = -HALF_SQRT_2*(x + y); + x = tmp; + return; + } + case ROTATION_YAW_270: { + tmp = x; x = y; y = -tmp; + return; + } + case ROTATION_YAW_315: { + tmp = HALF_SQRT_2*(x + y); + y = HALF_SQRT_2*(y - x); + x = tmp; + return; + } + case ROTATION_ROLL_180: { + y = -y; z = -z; + return; + } + case ROTATION_ROLL_180_YAW_45: { + tmp = HALF_SQRT_2*(x + y); + y = HALF_SQRT_2*(x - y); + x = tmp; z = -z; + return; + } + case ROTATION_ROLL_180_YAW_90: { + tmp = x; x = y; y = tmp; z = -z; + return; + } + case ROTATION_ROLL_180_YAW_135: { + tmp = HALF_SQRT_2*(y - x); + y = HALF_SQRT_2*(y + x); + x = tmp; z = -z; + return; + } + case ROTATION_PITCH_180: { + x = -x; z = -z; + return; + } + case ROTATION_ROLL_180_YAW_225: { + tmp = -HALF_SQRT_2*(x + y); + y = HALF_SQRT_2*(y - x); + x = tmp; z = -z; + return; + } + case ROTATION_ROLL_180_YAW_270: { + tmp = x; x = -y; y = -tmp; z = -z; + return; + } + case ROTATION_ROLL_180_YAW_315: { + tmp = HALF_SQRT_2*(x - y); + y = -HALF_SQRT_2*(x + y); + x = tmp; z = -z; + return; + } + case ROTATION_ROLL_90: { + tmp = z; z = y; y = -tmp; + return; + } + case ROTATION_ROLL_90_YAW_45: { + tmp = z; z = y; y = -tmp; + tmp = HALF_SQRT_2*(x - y); + y = HALF_SQRT_2*(x + y); + x = tmp; + return; + } + case ROTATION_ROLL_90_YAW_90: { + tmp = z; z = y; y = -tmp; + tmp = x; x = -y; y = tmp; + return; + } + case ROTATION_ROLL_90_YAW_135: { + tmp = z; z = y; y = -tmp; + tmp = -HALF_SQRT_2*(x + y); + y = HALF_SQRT_2*(x - y); + x = tmp; + return; + } + case ROTATION_ROLL_270: { + tmp = z; z = -y; y = tmp; + return; + } + case ROTATION_ROLL_270_YAW_45: { + tmp = z; z = -y; y = tmp; + tmp = HALF_SQRT_2*(x - y); + y = HALF_SQRT_2*(x + y); + x = tmp; + return; + } + case ROTATION_ROLL_270_YAW_90: { + tmp = z; z = -y; y = tmp; + tmp = x; x = -y; y = tmp; + return; + } + case ROTATION_ROLL_270_YAW_135: { + tmp = z; z = -y; y = tmp; + tmp = -HALF_SQRT_2*(x + y); + y = HALF_SQRT_2*(x - y); + x = tmp; + return; + } + case ROTATION_PITCH_90: { + tmp = z; z = -x; x = tmp; + return; + } + case ROTATION_PITCH_270: { + tmp = z; z = x; x = -tmp; + return; + } + } +} diff --git a/src/lib/conversion/rotation.h b/src/lib/conversion/rotation.h index 0c56494c5..5187b448f 100644 --- a/src/lib/conversion/rotation.h +++ b/src/lib/conversion/rotation.h @@ -118,4 +118,12 @@ const rot_lookup_t rot_lookup[] = { __EXPORT void get_rot_matrix(enum Rotation rot, math::Matrix<3,3> *rot_matrix); + +/** + * rotate a 3 element float vector in-place + */ +__EXPORT void +rotate_3f(enum Rotation rot, float &x, float &y, float &z); + + #endif /* ROTATION_H_ */ -- cgit v1.2.3 From c681d6621d8e4b29c3be8d8b94bf765b42f10e49 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 3 Jul 2014 14:02:28 +1000 Subject: mpu6000: added -R rotation option --- src/drivers/mpu6000/mpu6000.cpp | 32 +++++++++++++++++++++++--------- 1 file changed, 23 insertions(+), 9 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 7f9e9fde4..f6e00feee 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -72,6 +72,7 @@ #include #include #include +#include #define DIR_READ 0x80 #define DIR_WRITE 0x00 @@ -180,7 +181,7 @@ class MPU6000_gyro; class MPU6000 : public device::SPI { public: - MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device); + MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device, enum Rotation rotation); virtual ~MPU6000(); virtual int init(); @@ -235,6 +236,8 @@ private: math::LowPassFilter2p _gyro_filter_y; math::LowPassFilter2p _gyro_filter_z; + enum Rotation _rotation; + /** * Start automatic measurement. */ @@ -371,7 +374,7 @@ private: /** driver 'main' command */ extern "C" { __EXPORT int mpu6000_main(int argc, char *argv[]); } -MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device) : +MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev_e device, enum Rotation rotation) : SPI("MPU6000", path_accel, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED), _gyro(new MPU6000_gyro(this, path_gyro)), _product(0), @@ -394,7 +397,8 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev _accel_filter_z(MPU6000_ACCEL_DEFAULT_RATE, MPU6000_ACCEL_DEFAULT_DRIVER_FILTER_FREQ), _gyro_filter_x(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ), _gyro_filter_y(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ), - _gyro_filter_z(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ) + _gyro_filter_z(MPU6000_GYRO_DEFAULT_RATE, MPU6000_GYRO_DEFAULT_DRIVER_FILTER_FREQ), + _rotation(rotation) { // disable debug() calls _debug_enabled = false; @@ -1304,6 +1308,9 @@ MPU6000::measure() arb.y = _accel_filter_y.apply(y_in_new); arb.z = _accel_filter_z.apply(z_in_new); + // apply user specified rotation + rotate_3f(_rotation, arb.x, arb.y, arb.z); + arb.scaling = _accel_range_scale; arb.range_m_s2 = _accel_range_m_s2; @@ -1322,6 +1329,9 @@ MPU6000::measure() grb.y = _gyro_filter_y.apply(y_gyro_in_new); grb.z = _gyro_filter_z.apply(z_gyro_in_new); + // apply user specified rotation + rotate_3f(_rotation, grb.x, grb.y, grb.z); + grb.scaling = _gyro_range_scale; grb.range_rad_s = _gyro_range_rad_s; @@ -1419,7 +1429,7 @@ namespace mpu6000 MPU6000 *g_dev_int; // on internal bus MPU6000 *g_dev_ext; // on external bus -void start(bool); +void start(bool, enum Rotation); void test(bool); void reset(bool); void info(bool); @@ -1428,7 +1438,7 @@ void info(bool); * Start the driver. */ void -start(bool external_bus) +start(bool external_bus, enum Rotation rotation) { int fd; MPU6000 **g_dev_ptr = external_bus?&g_dev_int:&g_dev_ext; @@ -1442,12 +1452,12 @@ start(bool external_bus) /* create the driver */ if (external_bus) { #ifdef PX4_SPI_BUS_EXT - *g_dev_ptr = new MPU6000(PX4_SPI_BUS_EXT, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_EXT_MPU); + *g_dev_ptr = new MPU6000(PX4_SPI_BUS_EXT, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_EXT_MPU, rotation); #else errx(0, "External SPI not available"); #endif } else { - *g_dev_ptr = new MPU6000(PX4_SPI_BUS_SENSORS, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_MPU); + *g_dev_ptr = new MPU6000(PX4_SPI_BUS_SENSORS, path_accel, path_gyro, (spi_dev_e)PX4_SPIDEV_MPU, rotation); } if (*g_dev_ptr == nullptr) @@ -1610,13 +1620,17 @@ mpu6000_main(int argc, char *argv[]) { bool external_bus = false; int ch; + enum Rotation rotation = ROTATION_NONE; /* jump over start/off/etc and look at options first */ - while ((ch = getopt(argc, argv, "X")) != EOF) { + while ((ch = getopt(argc, argv, "XR:")) != EOF) { switch (ch) { case 'X': external_bus = true; break; + case 'R': + rotation = (enum Rotation)atoi(optarg); + break; default: mpu6000_usage(); exit(0); @@ -1630,7 +1644,7 @@ mpu6000_main(int argc, char *argv[]) */ if (!strcmp(verb, "start")) - mpu6000::start(external_bus); + mpu6000::start(external_bus, rotation); /* * Test the driver/device. -- cgit v1.2.3 From 1dfc7bad7b04af74d154b9c4bd3886f346f38d72 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 3 Jul 2014 14:06:52 +1000 Subject: Merged lsm303d update, keeping default frequency --- src/drivers/lsm303d/lsm303d.cpp | 33 +++++++++++++++++++++++---------- 1 file changed, 23 insertions(+), 10 deletions(-) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 0428901a3..f25ac8f87 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -69,6 +69,7 @@ #include #include +#include /* oddly, ERROR is not defined for c++ */ #ifdef ERROR @@ -222,7 +223,7 @@ class LSM303D_mag; class LSM303D : public device::SPI { public: - LSM303D(int bus, const char* path, spi_dev_e device); + LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rotation); virtual ~LSM303D(); virtual int init(); @@ -311,7 +312,8 @@ private: uint64_t _last_log_us; uint64_t _last_log_sync_us; uint64_t _last_log_reg_us; - uint64_t _last_log_alarm_us; + uint64_t _last_log_alarm_us; + enum Rotation _rotation; /** * Start automatic measurement. @@ -491,7 +493,7 @@ private: }; -LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) : +LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rotation) : SPI("LSM303D", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within safety margins for LSM303D */), _mag(new LSM303D_mag(this)), _call_accel_interval(0), @@ -525,7 +527,8 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device) : _last_log_us(0), _last_log_sync_us(0), _last_log_reg_us(0), - _last_log_alarm_us(0) + _last_log_alarm_us(0), + _rotation(rotation) { // enable debug() calls _debug_enabled = true; @@ -1541,6 +1544,9 @@ LSM303D::measure() accel_report.y = _accel_filter_y.apply(y_in_new); accel_report.z = _accel_filter_z.apply(z_in_new); + // apply user specified rotation + rotate_3f(_rotation, accel_report.x, accel_report.y, accel_report.z); + accel_report.scaling = _accel_range_scale; accel_report.range_m_s2 = _accel_range_m_s2; @@ -1617,6 +1623,9 @@ LSM303D::mag_measure() mag_report.scaling = _mag_range_scale; mag_report.range_ga = (float)_mag_range_ga; + // apply user specified rotation + rotate_3f(_rotation, mag_report.x, mag_report.y, mag_report.z); + _mag_reports->force(&mag_report); /* XXX please check this poll_notify, is it the right one? */ @@ -1782,7 +1791,7 @@ namespace lsm303d LSM303D *g_dev; -void start(); +void start(bool external_bus, enum Rotation rotation); void test(); void reset(); void info(); @@ -1793,7 +1802,7 @@ void logging(); * Start the driver. */ void -start(bool external_bus) +start(bool external_bus, enum Rotation rotation) { int fd, fd_mag; if (g_dev != nullptr) @@ -1801,9 +1810,9 @@ start(bool external_bus) /* create the driver */ if (external_bus) { - g_dev = new LSM303D(PX4_SPI_BUS_EXT, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_EXT_ACCEL_MAG); + g_dev = new LSM303D(PX4_SPI_BUS_EXT, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_EXT_ACCEL_MAG, rotation); } else { - g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG); + g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG, rotation); } if (g_dev == nullptr) { warnx("failed instantiating LSM303D obj"); @@ -2015,13 +2024,17 @@ lsm303d_main(int argc, char *argv[]) { bool external_bus = false; int ch; + enum Rotation rotation = ROTATION_NONE; /* jump over start/off/etc and look at options first */ - while ((ch = getopt(argc, argv, "X")) != EOF) { + while ((ch = getopt(argc, argv, "XR:")) != EOF) { switch (ch) { case 'X': external_bus = true; break; + case 'R': + rotation = (enum Rotation)atoi(optarg); + break; default: lsm303d_usage(); exit(0); @@ -2035,7 +2048,7 @@ lsm303d_main(int argc, char *argv[]) */ if (!strcmp(verb, "start")) - lsm303d::start(external_bus); + lsm303d::start(external_bus, rotation); /* * Test the driver/device. -- cgit v1.2.3 From a049f0841d0a68edf2f1e5d10ba2ab24d15aa472 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 3 Jul 2014 14:10:38 +1000 Subject: Merged L3GD20 orientation flag while keeping original bus speed --- src/drivers/l3gd20/l3gd20.cpp | 29 ++++++++++++++++++++--------- 1 file changed, 20 insertions(+), 9 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 06b36d688..f8cd509a2 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -69,6 +69,7 @@ #include #include +#include #define L3GD20_DEVICE_PATH "/dev/l3gd20" @@ -185,7 +186,7 @@ extern "C" { __EXPORT int l3gd20_main(int argc, char *argv[]); } class L3GD20 : public device::SPI { public: - L3GD20(int bus, const char* path, spi_dev_e device); + L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotation); virtual ~L3GD20(); virtual int init(); @@ -230,6 +231,8 @@ private: /* true if an L3G4200D is detected */ bool _is_l3g4200d; + enum Rotation _rotation; + /** * Start automatic measurement. */ @@ -329,7 +332,7 @@ private: int self_test(); }; -L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) : +L3GD20::L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotation) : SPI("L3GD20", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within margins for L3GD20 */), _call_interval(0), _reports(nullptr), @@ -346,7 +349,8 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device) : _gyro_filter_x(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ), _gyro_filter_y(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ), _gyro_filter_z(L3GD20_DEFAULT_RATE, L3GD20_DEFAULT_FILTER_FREQ), - _is_l3g4200d(false) + _is_l3g4200d(false), + _rotation(rotation) { // enable debug() calls _debug_enabled = true; @@ -915,6 +919,9 @@ L3GD20::measure() report.y = _gyro_filter_y.apply(report.y); report.z = _gyro_filter_z.apply(report.z); + // apply user specified rotation + rotate_3f(_rotation, report.x, report.y, report.z); + report.scaling = _gyro_range_scale; report.range_rad_s = _gyro_range_rad_s; @@ -975,7 +982,7 @@ namespace l3gd20 L3GD20 *g_dev; -void start(); +void start(bool external_bus, enum Rotation rotation); void test(); void reset(); void info(); @@ -984,7 +991,7 @@ void info(); * Start the driver. */ void -start(bool external_bus) +start(bool external_bus, enum Rotation rotation) { int fd; @@ -994,12 +1001,12 @@ start(bool external_bus) /* create the driver */ if (external_bus) { #ifdef PX4_SPI_BUS_EXT - g_dev = new L3GD20(PX4_SPI_BUS_EXT, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_EXT_GYRO); + g_dev = new L3GD20(PX4_SPI_BUS_EXT, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_EXT_GYRO, rotation); #else errx(0, "External SPI not available"); #endif } else { - g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO); + g_dev = new L3GD20(PX4_SPI_BUS_SENSORS, L3GD20_DEVICE_PATH, (spi_dev_e)PX4_SPIDEV_GYRO, rotation); } if (g_dev == nullptr) @@ -1128,13 +1135,17 @@ l3gd20_main(int argc, char *argv[]) { bool external_bus = false; int ch; + enum Rotation rotation = ROTATION_NONE; /* jump over start/off/etc and look at options first */ - while ((ch = getopt(argc, argv, "X")) != EOF) { + while ((ch = getopt(argc, argv, "XR:")) != EOF) { switch (ch) { case 'X': external_bus = true; break; + case 'R': + rotation = (enum Rotation)atoi(optarg); + break; default: l3gd20_usage(); exit(0); @@ -1148,7 +1159,7 @@ l3gd20_main(int argc, char *argv[]) */ if (!strcmp(verb, "start")) - l3gd20::start(external_bus); + l3gd20::start(external_bus, rotation); /* * Test the driver/device. -- cgit v1.2.3 From d2487e771884d62f893b14629caae8437bd6998e Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 4 Jul 2014 11:20:14 +1000 Subject: hmc5883: added support for -R rotation option --- src/drivers/hmc5883/hmc5883.cpp | 45 +++++++++++++++++++++++++++++++++-------- 1 file changed, 37 insertions(+), 8 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index b7b368a5e..75acf32e3 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -71,6 +71,8 @@ #include #include +#include +#include /* * HMC5883 internal constants and data structures. @@ -130,7 +132,7 @@ static const int ERROR = -1; class HMC5883 : public device::I2C { public: - HMC5883(int bus); + HMC5883(int bus, enum Rotation rotation); virtual ~HMC5883(); virtual int init(); @@ -169,6 +171,7 @@ private: bool _calibrated; /**< the calibration is valid */ int _bus; /**< the bus the device is connected to */ + enum Rotation _rotation; struct mag_report _last_report; /**< used for info() */ @@ -319,7 +322,7 @@ private: extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]); -HMC5883::HMC5883(int bus) : +HMC5883::HMC5883(int bus, enum Rotation rotation) : I2C("HMC5883", HMC5883L_DEVICE_PATH, bus, HMC5883L_ADDRESS, 400000), _measure_ticks(0), _reports(nullptr), @@ -334,7 +337,8 @@ HMC5883::HMC5883(int bus) : _buffer_overflows(perf_alloc(PC_COUNT, "hmc5883_buffer_overflows")), _sensor_ok(false), _calibrated(false), - _bus(bus) + _bus(bus), + _rotation(rotation) { // enable debug() calls _debug_enabled = false; @@ -862,6 +866,9 @@ HMC5883::collect() /* z remains z */ new_report.z = ((report.z * _range_scale) - _scale.z_offset) * _scale.z_scale; + // apply user specified rotation + rotate_3f(_rotation, new_report.x, new_report.y, new_report.z); + if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { if (_mag_topic != -1) { @@ -1246,7 +1253,7 @@ const int ERROR = -1; HMC5883 *g_dev; -void start(); +void start(enum Rotation rotation); void test(); void reset(); void info(); @@ -1256,7 +1263,7 @@ int calibrate(); * Start the driver. */ void -start() +start(enum Rotation rotation) { int fd; @@ -1265,7 +1272,7 @@ start() errx(0, "already started"); /* create the driver, attempt expansion bus first */ - g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION); + g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION, rotation); if (g_dev != nullptr && OK != g_dev->init()) { delete g_dev; g_dev = nullptr; @@ -1275,7 +1282,7 @@ start() #ifdef PX4_I2C_BUS_ONBOARD /* if this failed, attempt onboard sensor */ if (g_dev == nullptr) { - g_dev = new HMC5883(PX4_I2C_BUS_ONBOARD); + g_dev = new HMC5883(PX4_I2C_BUS_ONBOARD, rotation); if (g_dev != nullptr && OK != g_dev->init()) { goto fail; } @@ -1474,14 +1481,36 @@ info() } // namespace +void +hmc5883_usage() +{ + warnx("missing command: try 'start', 'info', 'test', 'reset', 'info', 'calibrate'"); + warnx("options:"); + warnx(" -R rotation"); +} + int hmc5883_main(int argc, char *argv[]) { + int ch; + enum Rotation rotation = ROTATION_NONE; + + while ((ch = getopt(argc, argv, "R:")) != EOF) { + switch (ch) { + case 'R': + rotation = (enum Rotation)atoi(optarg); + break; + default: + hmc5883_usage(); + exit(0); + } + } + /* * Start/load the driver. */ if (!strcmp(argv[1], "start")) - hmc5883::start(); + hmc5883::start(rotation); /* * Test the driver/device. -- cgit v1.2.3 From d952e81ab7c5ef050784cf3766c5b7bf18909777 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 4 Jul 2014 11:48:44 +1000 Subject: added support for two instances of hmc5883 driver --- src/drivers/hmc5883/hmc5883.cpp | 115 +++++++++++++++++++++++++--------------- 1 file changed, 72 insertions(+), 43 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 75acf32e3..b9270d2a0 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -79,7 +79,8 @@ */ #define HMC5883L_ADDRESS PX4_I2C_OBDEV_HMC5883 -#define HMC5883L_DEVICE_PATH "/dev/hmc5883" +#define HMC5883L_DEVICE_PATH_INT "/dev/hmc5883_int" +#define HMC5883L_DEVICE_PATH_EXT "/dev/hmc5883_ext" /* Max measurement rate is 160Hz, however with 160 it will be set to 166 Hz, therefore workaround using 150 */ #define HMC5883_CONVERSION_INTERVAL (1000000 / 150) /* microseconds */ @@ -132,7 +133,7 @@ static const int ERROR = -1; class HMC5883 : public device::I2C { public: - HMC5883(int bus, enum Rotation rotation); + HMC5883(int bus, const char *path, enum Rotation rotation); virtual ~HMC5883(); virtual int init(); @@ -322,8 +323,8 @@ private: extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]); -HMC5883::HMC5883(int bus, enum Rotation rotation) : - I2C("HMC5883", HMC5883L_DEVICE_PATH, bus, HMC5883L_ADDRESS, 400000), +HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) : + I2C("HMC5883", path, bus, HMC5883L_ADDRESS, 400000), _measure_ticks(0), _reports(nullptr), _range_scale(0), /* default range scale from counts to gauss */ @@ -1251,13 +1252,14 @@ namespace hmc5883 #endif const int ERROR = -1; -HMC5883 *g_dev; +HMC5883 *g_dev_int; +HMC5883 *g_dev_ext; -void start(enum Rotation rotation); -void test(); -void reset(); +void start(int bus, enum Rotation rotation); +void test(int bus); +void reset(int bus); void info(); -int calibrate(); +int calibrate(int bus); /** * Start the driver. @@ -1267,47 +1269,69 @@ start(enum Rotation rotation) { int fd; - if (g_dev != nullptr) - /* if already started, the still command succeeded */ - errx(0, "already started"); - /* create the driver, attempt expansion bus first */ - g_dev = new HMC5883(PX4_I2C_BUS_EXPANSION, rotation); - if (g_dev != nullptr && OK != g_dev->init()) { - delete g_dev; - g_dev = nullptr; + if (bus == -1 || bus == PX4_I2C_BUS_EXPANSION) { + if (g_dev_ext != nullptr) + errx(0, "already started external"); + g_dev_ext = new HMC5883(PX4_I2C_BUS_EXPANSION, HMC5883L_DEVICE_PATH_EXT, rotation); + if (g_dev_ext != nullptr && OK != g_dev_ext->init()) { + delete g_dev_ext; + g_dev_ext = nullptr; + } } #ifdef PX4_I2C_BUS_ONBOARD /* if this failed, attempt onboard sensor */ - if (g_dev == nullptr) { - g_dev = new HMC5883(PX4_I2C_BUS_ONBOARD, rotation); - if (g_dev != nullptr && OK != g_dev->init()) { + if (bus == -1 || bus == PX4_I2C_BUS_ONBOARD) { + if (g_dev_int != nullptr) + errx(0, "already started internal"); + g_dev_int = new HMC5883(PX4_I2C_BUS_ONBOARD, HMC5883L_DEVICE_PATH_INT, rotation); + if (g_dev_int != nullptr && OK != g_dev_int->init()) { + if (bus == PX4_I2C_BUS_ONBOARD) { + goto fail; + } + } + if (g_dev_int == nullptr && bus == PX4_I2C_BUS_ONBOARD) { goto fail; } } #endif - if (g_dev == nullptr) + if (g_dev_int == nullptr && g_dev_ext == nullptr) goto fail; /* set the poll rate to default, starts automatic data collection */ - fd = open(HMC5883L_DEVICE_PATH, O_RDONLY); + if (g_dev_int != nullptr) { + fd = open(HMC5883L_DEVICE_PATH_INT, O_RDONLY); + if (fd < 0) + goto fail; - if (fd < 0) - goto fail; + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) + goto fail; + close(fd); + } - if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) - goto fail; + if (g_dev_ext != nullptr) { + fd = open(HMC5883L_DEVICE_PATH_EXT, O_RDONLY); + if (fd < 0) + goto fail; + + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) + goto fail; + close(fd); + } exit(0); fail: - - if (g_dev != nullptr) { - delete g_dev; - g_dev = nullptr; + if (g_dev_int != nullptr) { + delete g_dev_int; + g_dev_int = nullptr; + } + if (g_dev_ext != nullptr) { + delete g_dev_ext; + g_dev_ext = nullptr; } errx(1, "driver start failed"); @@ -1319,16 +1343,17 @@ fail: * and automatic modes. */ void -test() +test(int bus) { struct mag_report report; ssize_t sz; int ret; + const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT); - int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY); + int fd = open(path, O_RDONLY); if (fd < 0) - err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", HMC5883L_DEVICE_PATH); + err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", path); /* do a simple demand read */ sz = read(fd, &report, sizeof(report)); @@ -1421,14 +1446,15 @@ test() * configuration register A back to 00 (Normal Measurement Mode), e.g. 0x10. * Using the self test method described above, the user can scale sensor */ -int calibrate() +int calibrate(int bus) { int ret; + const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT); - int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY); + int fd = open(path, O_RDONLY); if (fd < 0) - err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", HMC5883L_DEVICE_PATH); + err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", path); if (OK != (ret = ioctl(fd, MAGIOCCALIBRATE, fd))) { warnx("failed to enable sensor calibration mode"); @@ -1448,9 +1474,11 @@ int calibrate() * Reset the driver. */ void -reset() +reset(int bus) { - int fd = open(HMC5883L_DEVICE_PATH, O_RDONLY); + const char *path = (bus==PX4_I2C_BUS_ONBOARD?HMC5883L_DEVICE_PATH_INT:HMC5883L_DEVICE_PATH_EXT); + + int fd = open(path, O_RDONLY); if (fd < 0) err(1, "failed "); @@ -1468,8 +1496,9 @@ reset() * Print a little info about the driver. */ void -info() +info(int bus) { + HMC5883 *g_dev = (bus == PX4_I2C_BUS_ONBOARD?g_dev_int:g_dev_ext); if (g_dev == nullptr) errx(1, "driver not running"); @@ -1516,25 +1545,25 @@ hmc5883_main(int argc, char *argv[]) * Test the driver/device. */ if (!strcmp(argv[1], "test")) - hmc5883::test(); + hmc5883::test(bus); /* * Reset the driver. */ if (!strcmp(argv[1], "reset")) - hmc5883::reset(); + hmc5883::reset(bus); /* * Print driver information. */ if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) - hmc5883::info(); + hmc5883::info(bus); /* * Autocalibrate the scaling */ if (!strcmp(argv[1], "calibrate")) { - if (hmc5883::calibrate() == 0) { + if (hmc5883::calibrate(bus) == 0) { errx(0, "calibration successful"); } else { -- cgit v1.2.3 From 5e62ae7a9e2a7d3ea05d293900f7171884fbb448 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 4 Jul 2014 12:07:23 +1000 Subject: hmc5883: added -C option to calibrate on startup Conflicts: src/drivers/hmc5883/hmc5883.cpp --- src/drivers/hmc5883/hmc5883.cpp | 42 ++++++++++++++++++++++++++++++++++------- 1 file changed, 35 insertions(+), 7 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index b9270d2a0..65c8c64d0 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1516,6 +1516,11 @@ hmc5883_usage() warnx("missing command: try 'start', 'info', 'test', 'reset', 'info', 'calibrate'"); warnx("options:"); warnx(" -R rotation"); + warnx(" -C calibrate on start"); + warnx(" -X only external bus"); +#ifdef PX4_I2C_BUS_ONBOARD + warnx(" -I only internal bus"); +#endif } int @@ -1523,46 +1528,69 @@ hmc5883_main(int argc, char *argv[]) { int ch; enum Rotation rotation = ROTATION_NONE; + bool calibrate = false; - while ((ch = getopt(argc, argv, "R:")) != EOF) { + while ((ch = getopt(argc, argv, "XIR:C")) != EOF) { switch (ch) { case 'R': rotation = (enum Rotation)atoi(optarg); break; +#ifdef PX4_I2C_BUS_ONBOARD + case 'I': + bus = PX4_I2C_BUS_ONBOARD; + break; +#endif + case 'X': + bus = PX4_I2C_BUS_EXPANSION; + break; + case 'C': + calibrate = true; + break; default: hmc5883_usage(); exit(0); } } + const char *verb = argv[optind]; + /* * Start/load the driver. */ - if (!strcmp(argv[1], "start")) - hmc5883::start(rotation); + if (!strcmp(verb, "start")) { + hmc5883::start(bus, rotation); + if (calibrate) { + if (hmc5883::calibrate(bus) == 0) { + errx(0, "calibration successful"); + + } else { + errx(1, "calibration failed"); + } + } + } /* * Test the driver/device. */ - if (!strcmp(argv[1], "test")) + if (!strcmp(verb, "test")) hmc5883::test(bus); /* * Reset the driver. */ - if (!strcmp(argv[1], "reset")) + if (!strcmp(verb, "reset")) hmc5883::reset(bus); /* * Print driver information. */ - if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) + if (!strcmp(verb, "info") || !strcmp(verb, "status")) hmc5883::info(bus); /* * Autocalibrate the scaling */ - if (!strcmp(argv[1], "calibrate")) { + if (!strcmp(verb, "calibrate")) { if (hmc5883::calibrate(bus) == 0) { errx(0, "calibration successful"); -- cgit v1.2.3 From dfee93f3b128a7f23d74363b7700c80ababbe690 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 6 Jul 2014 22:37:40 +1000 Subject: hmc5883: fixed driver startup when trying both buses --- src/drivers/hmc5883/hmc5883.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 65c8c64d0..25cbc0679 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1325,11 +1325,11 @@ start(enum Rotation rotation) exit(0); fail: - if (g_dev_int != nullptr) { + if (g_dev_int != nullptr && (bus == -1 || bus == PX4_I2C_BUS_ONBOARD)) { delete g_dev_int; g_dev_int = nullptr; } - if (g_dev_ext != nullptr) { + if (g_dev_ext != nullptr && (bus == -1 || bus == PX4_I2C_BUS_EXPANSION)) { delete g_dev_ext; g_dev_ext = nullptr; } -- cgit v1.2.3 From 1c6ea067902708a2b1b3faf55938e6e8768abe18 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Jul 2014 08:52:16 +1000 Subject: hmc5883: fixed build warnings --- src/drivers/hmc5883/hmc5883.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 25cbc0679..72d6bdd95 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1255,10 +1255,11 @@ const int ERROR = -1; HMC5883 *g_dev_int; HMC5883 *g_dev_ext; +void hmc5883_usage(); void start(int bus, enum Rotation rotation); void test(int bus); void reset(int bus); -void info(); +void info(int bus); int calibrate(int bus); /** -- cgit v1.2.3 From 42716345859ded979189ea7f2548d512975c4dec Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 7 Jul 2014 08:52:27 +1000 Subject: l3gd20: fixed a build warning --- src/drivers/l3gd20/l3gd20.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index f8cd509a2..cad3ff937 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -982,6 +982,7 @@ namespace l3gd20 L3GD20 *g_dev; +void l3gd20_usage(); void start(bool external_bus, enum Rotation rotation); void test(); void reset(); -- cgit v1.2.3 From 1b555f2d2e0684485fa47db7acfcf5555a7c6b16 Mon Sep 17 00:00:00 2001 From: akdslr Date: Tue, 15 Apr 2014 15:28:30 -0400 Subject: LL40LS driver: Added new driver to the config make files --- makefiles/config_px4fmu-v1_default.mk | 1 + makefiles/config_px4fmu-v2_default.mk | 1 + 2 files changed, 2 insertions(+) diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index 4d727aa4d..cc0958c29 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -25,6 +25,7 @@ MODULES += drivers/mpu6000 MODULES += drivers/hmc5883 MODULES += drivers/ms5611 MODULES += drivers/mb12xx +MODULES += drivers/ll40ls MODULES += drivers/gps MODULES += drivers/hil MODULES += drivers/hott/hott_telemetry diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index 8e83df391..adfbc2b7d 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -28,6 +28,7 @@ MODULES += drivers/hmc5883 MODULES += drivers/ms5611 MODULES += drivers/mb12xx MODULES += drivers/sf0x +MODULES += drivers/ll40ls MODULES += drivers/gps MODULES += drivers/hil MODULES += drivers/hott/hott_telemetry -- cgit v1.2.3 From 36a9123822dca314f4efc4b4cb140159dbe9e634 Mon Sep 17 00:00:00 2001 From: akdslr Date: Tue, 15 Apr 2014 20:50:31 -0400 Subject: LL40LS driver: adding new range finder driver --- src/drivers/ll40ls/ll40ls.cpp | 880 ++++++++++++++++++++++++++++++++++++++++++ src/drivers/ll40ls/module.mk | 40 ++ 2 files changed, 920 insertions(+) create mode 100644 src/drivers/ll40ls/ll40ls.cpp create mode 100644 src/drivers/ll40ls/module.mk diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp new file mode 100644 index 000000000..cb0eac91b --- /dev/null +++ b/src/drivers/ll40ls/ll40ls.cpp @@ -0,0 +1,880 @@ +/**************************************************************************** + * + * Copyright (c) 2013 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file ll40ls.cpp + * @author Allyson Kreft + * + * Driver for the PulsedLight Lidar-Lite range finders connected via I2C. + */ + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include + +#include + +/* Configuration Constants */ +#define LL40LS_BUS PX4_I2C_BUS_EXPANSION +#define LL40LS_BASEADDR 0x42 /* 7-bit address */ +#define LL40LS_DEVICE_PATH "/dev/ll40ls" + +/* LL40LS Registers addresses */ + +#define LL40LS_MEASURE_REG 0x00 /* Measure range register */ +#define LL40LS_MSRREG_ACQUIRE 0x61 /* Value to initiate a measurement */ +#define LL40LS_DISTHIGH_REG 0x8F /* High byte of distance register, auto increment */ + +/* Device limits */ +#define LL40LS_MIN_DISTANCE (0.00f) +#define LL40LS_MAX_DISTANCE (14.00f) + +#define LL40LS_CONVERSION_INTERVAL 60000 /* 60ms */ + +/* oddly, ERROR is not defined for c++ */ +#ifdef ERROR +# undef ERROR +#endif +static const int ERROR = -1; + +#ifndef CONFIG_SCHED_WORKQUEUE +# error This requires CONFIG_SCHED_WORKQUEUE. +#endif + +class LL40LS : public device::I2C +{ +public: + LL40LS(int bus = LL40LS_BUS, int address = LL40LS_BASEADDR); + virtual ~LL40LS(); + + virtual int init(); + + virtual ssize_t read(struct file *filp, char *buffer, size_t buflen); + virtual int ioctl(struct file *filp, int cmd, unsigned long arg); + + /** + * Diagnostics - print some basic information about the driver. + */ + void print_info(); + +protected: + virtual int probe(); + +private: + float _min_distance; + float _max_distance; + work_s _work; + RingBuffer *_reports; + bool _sensor_ok; + int _measure_ticks; + bool _collect_phase; + int _class_instance; + + orb_advert_t _range_finder_topic; + + perf_counter_t _sample_perf; + perf_counter_t _comms_errors; + perf_counter_t _buffer_overflows; + + /** + * Test whether the device supported by the driver is present at a + * specific address. + * + * @param address The I2C bus address to probe. + * @return True if the device is present. + */ + int probe_address(uint8_t address); + + /** + * Initialise the automatic measurement state machine and start it. + * + * @note This function is called at open and error time. It might make sense + * to make it more aggressive about resetting the bus in case of errors. + */ + void start(); + + /** + * Stop the automatic measurement state machine. + */ + void stop(); + + /** + * Set the min and max distance thresholds if you want the end points of the sensors + * range to be brought in at all, otherwise it will use the defaults LL40LS_MIN_DISTANCE + * and LL40LS_MAX_DISTANCE + */ + void set_minimum_distance(float min); + void set_maximum_distance(float max); + float get_minimum_distance(); + float get_maximum_distance(); + + /** + * Perform a poll cycle; collect from the previous measurement + * and start a new one. + */ + void cycle(); + int measure(); + int collect(); + /** + * Static trampoline from the workq context; because we don't have a + * generic workq wrapper yet. + * + * @param arg Instance pointer for the driver that is polling. + */ + static void cycle_trampoline(void *arg); + + +}; + +/* + * Driver 'main' command. + */ +extern "C" __EXPORT int ll40ls_main(int argc, char *argv[]); + +LL40LS::LL40LS(int bus, int address) : + I2C("LL40LS", LL40LS_DEVICE_PATH, bus, address, 100000), + _min_distance(LL40LS_MIN_DISTANCE), + _max_distance(LL40LS_MAX_DISTANCE), + _reports(nullptr), + _sensor_ok(false), + _measure_ticks(0), + _collect_phase(false), + _range_finder_topic(-1), + _class_instance(-1), + _sample_perf(perf_alloc(PC_ELAPSED, "ll40ls_read")), + _comms_errors(perf_alloc(PC_COUNT, "ll40ls_comms_errors")), + _buffer_overflows(perf_alloc(PC_COUNT, "ll40ls_buffer_overflows")) +{ + // up the retries since the device misses the first measure attempts + I2C::_retries = 3; + + // enable debug() calls + _debug_enabled = false; + + // work_cancel in the dtor will explode if we don't do this... + memset(&_work, 0, sizeof(_work)); +} + +LL40LS::~LL40LS() +{ + /* make sure we are truly inactive */ + stop(); + + /* free any existing reports */ + if (_reports != nullptr) { + delete _reports; + } + + if (_class_instance != -1) { + unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance); + } + + // free perf counters + perf_free(_sample_perf); + perf_free(_comms_errors); + perf_free(_buffer_overflows); +} + +int +LL40LS::init() +{ + int ret = ERROR; + + /* do I2C init (and probe) first */ + if (I2C::init() != OK) { + goto out; + } + + /* allocate basic report buffers */ + _reports = new RingBuffer(2, sizeof(range_finder_report)); + + if (_reports == nullptr) { + goto out; + } + + _class_instance = register_class_devname(RANGE_FINDER_DEVICE_PATH); + + if (_class_instance == CLASS_DEVICE_PRIMARY) { + /* get a publish handle on the range finder topic */ + struct range_finder_report rf_report; + measure(); + _reports->get(&rf_report); + _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report); + + if (_range_finder_topic < 0) { + debug("failed to create sensor_range_finder object. Did you start uOrb?"); + } + } + + ret = OK; + /* sensor is ok, but we don't really know if it is within range */ + _sensor_ok = true; +out: + return ret; +} + +int +LL40LS::probe() +{ + return measure(); +} + +void +LL40LS::set_minimum_distance(float min) +{ + _min_distance = min; +} + +void +LL40LS::set_maximum_distance(float max) +{ + _max_distance = max; +} + +float +LL40LS::get_minimum_distance() +{ + return _min_distance; +} + +float +LL40LS::get_maximum_distance() +{ + return _max_distance; +} + +int +LL40LS::ioctl(struct file *filp, int cmd, unsigned long arg) +{ + switch (cmd) { + + case SENSORIOCSPOLLRATE: { + switch (arg) { + + /* switching to manual polling */ + case SENSOR_POLLRATE_MANUAL: + stop(); + _measure_ticks = 0; + return OK; + + /* external signalling (DRDY) not supported */ + case SENSOR_POLLRATE_EXTERNAL: + + /* zero would be bad */ + case 0: + return -EINVAL; + + /* set default/max polling rate */ + case SENSOR_POLLRATE_MAX: + case SENSOR_POLLRATE_DEFAULT: { + /* do we need to start internal polling? */ + bool want_start = (_measure_ticks == 0); + + /* set interval for next measurement to minimum legal value */ + _measure_ticks = USEC2TICK(LL40LS_CONVERSION_INTERVAL); + + /* if we need to start the poll state machine, do it */ + if (want_start) { + start(); + } + + return OK; + } + + /* adjust to a legal polling interval in Hz */ + default: { + /* do we need to start internal polling? */ + bool want_start = (_measure_ticks == 0); + + /* convert hz to tick interval via microseconds */ + unsigned ticks = USEC2TICK(1000000 / arg); + + /* check against maximum rate */ + if (ticks < USEC2TICK(LL40LS_CONVERSION_INTERVAL)) { + return -EINVAL; + } + + /* update interval for next measurement */ + _measure_ticks = ticks; + + /* if we need to start the poll state machine, do it */ + if (want_start) { + start(); + } + + return OK; + } + } + } + + case SENSORIOCGPOLLRATE: + if (_measure_ticks == 0) { + return SENSOR_POLLRATE_MANUAL; + } + + return (1000 / _measure_ticks); + + case SENSORIOCSQUEUEDEPTH: { + /* lower bound is mandatory, upper bound is a sanity check */ + if ((arg < 1) || (arg > 100)) { + return -EINVAL; + } + + irqstate_t flags = irqsave(); + + if (!_reports->resize(arg)) { + irqrestore(flags); + return -ENOMEM; + } + + irqrestore(flags); + + return OK; + } + + case SENSORIOCGQUEUEDEPTH: + return _reports->size(); + + case SENSORIOCRESET: + /* XXX implement this */ + return -EINVAL; + + case RANGEFINDERIOCSETMINIUMDISTANCE: { + set_minimum_distance(*(float *)arg); + return 0; + } + break; + + case RANGEFINDERIOCSETMAXIUMDISTANCE: { + set_maximum_distance(*(float *)arg); + return 0; + } + break; + + default: + /* give it to the superclass */ + return I2C::ioctl(filp, cmd, arg); + } +} + +ssize_t +LL40LS::read(struct file *filp, char *buffer, size_t buflen) +{ + unsigned count = buflen / sizeof(struct range_finder_report); + struct range_finder_report *rbuf = reinterpret_cast(buffer); + int ret = 0; + + /* buffer must be large enough */ + if (count < 1) { + return -ENOSPC; + } + + /* if automatic measurement is enabled */ + if (_measure_ticks > 0) { + + /* + * While there is space in the caller's buffer, and reports, copy them. + * Note that we may be pre-empted by the workq thread while we are doing this; + * we are careful to avoid racing with them. + */ + while (count--) { + if (_reports->get(rbuf)) { + ret += sizeof(*rbuf); + rbuf++; + } + } + + /* if there was no data, warn the caller */ + return ret ? ret : -EAGAIN; + } + + /* manual measurement - run one conversion */ + do { + _reports->flush(); + + /* trigger a measurement */ + if (OK != measure()) { + ret = -EIO; + break; + } + + /* wait for it to complete */ + usleep(LL40LS_CONVERSION_INTERVAL); + + /* run the collection phase */ + if (OK != collect()) { + ret = -EIO; + break; + } + + /* state machine will have generated a report, copy it out */ + if (_reports->get(rbuf)) { + ret = sizeof(*rbuf); + } + + } while (0); + + return ret; +} + +int +LL40LS::measure() +{ + int ret; + + /* + * Send the command to begin a measurement. + */ + const uint8_t cmd[2] = { LL40LS_MEASURE_REG, LL40LS_MSRREG_ACQUIRE }; + ret = transfer(cmd, sizeof(cmd), nullptr, 0); + + if (OK != ret) { + perf_count(_comms_errors); + log("i2c::transfer returned %d", ret); + return ret; + } + + ret = OK; + + return ret; +} + +int +LL40LS::collect() +{ + int ret = -EIO; + + /* read from the sensor */ + uint8_t val[2] = {0, 0}; + + perf_begin(_sample_perf); + + // read the high and low byte distance registers + uint8_t distance_reg = LL40LS_DISTHIGH_REG; + ret = transfer(&distance_reg, 1, &val[0], sizeof(val)); + + if (ret < 0) { + log("error reading from sensor: %d", ret); + perf_count(_comms_errors); + perf_end(_sample_perf); + return ret; + } + + uint16_t distance = val[0] << 8 | val[1]; + float si_units = (distance * 1.0f) / 100.0f; /* cm to m */ + struct range_finder_report report; + + /* this should be fairly close to the end of the measurement, so the best approximation of the time */ + report.timestamp = hrt_absolute_time(); + report.error_count = perf_event_count(_comms_errors); + report.distance = si_units; + if (si_units > get_minimum_distance() && si_units < get_maximum_distance()) { + report.valid = 1; + } + else { + report.valid = 0; + } + + /* publish it */ + orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report); + + if (_reports->force(&report)) { + perf_count(_buffer_overflows); + } + + /* notify anyone waiting for data */ + poll_notify(POLLIN); + + ret = OK; + + perf_end(_sample_perf); + return ret; +} + +void +LL40LS::start() +{ + /* reset the report ring and state machine */ + _collect_phase = false; + _reports->flush(); + + /* schedule a cycle to start things */ + work_queue(HPWORK, &_work, (worker_t)&LL40LS::cycle_trampoline, this, 1); + + /* notify about state change */ + struct subsystem_info_s info = { + true, + true, + true, + SUBSYSTEM_TYPE_RANGEFINDER + }; + static orb_advert_t pub = -1; + + if (pub > 0) { + orb_publish(ORB_ID(subsystem_info), pub, &info); + + } else { + pub = orb_advertise(ORB_ID(subsystem_info), &info); + } +} + +void +LL40LS::stop() +{ + work_cancel(HPWORK, &_work); +} + +void +LL40LS::cycle_trampoline(void *arg) +{ + LL40LS *dev = (LL40LS *)arg; + + dev->cycle(); +} + +void +LL40LS::cycle() +{ + /* collection phase? */ + if (_collect_phase) { + + /* perform collection */ + if (OK != collect()) { + log("collection error"); + /* restart the measurement state machine */ + start(); + return; + } + + /* next phase is measurement */ + _collect_phase = false; + + /* + * Is there a collect->measure gap? + */ + if (_measure_ticks > USEC2TICK(LL40LS_CONVERSION_INTERVAL)) { + + /* schedule a fresh cycle call when we are ready to measure again */ + work_queue(HPWORK, + &_work, + (worker_t)&LL40LS::cycle_trampoline, + this, + _measure_ticks - USEC2TICK(LL40LS_CONVERSION_INTERVAL)); + + return; + } + } + + /* measurement phase */ + if (OK != measure()) { + log("measure error"); + } + + /* next phase is collection */ + _collect_phase = true; + + /* schedule a fresh cycle call when the measurement is done */ + work_queue(HPWORK, + &_work, + (worker_t)&LL40LS::cycle_trampoline, + this, + USEC2TICK(LL40LS_CONVERSION_INTERVAL)); +} + +void +LL40LS::print_info() +{ + perf_print_counter(_sample_perf); + perf_print_counter(_comms_errors); + perf_print_counter(_buffer_overflows); + printf("poll interval: %u ticks\n", _measure_ticks); + _reports->print_info("report queue"); +} + +/** + * Local functions in support of the shell command. + */ +namespace ll40ls +{ + +/* oddly, ERROR is not defined for c++ */ +#ifdef ERROR +# undef ERROR +#endif +const int ERROR = -1; + +LL40LS *g_dev; + +void start(); +void stop(); +void test(); +void reset(); +void info(); + +/** + * Start the driver. + */ +void +start() +{ + int fd; + + if (g_dev != nullptr) { + errx(1, "already started"); + } + + /* create the driver */ + g_dev = new LL40LS(LL40LS_BUS); + + if (g_dev == nullptr) { + goto fail; + } + + if (OK != g_dev->init()) { + goto fail; + } + + /* set the poll rate to default, starts automatic data collection */ + fd = open(LL40LS_DEVICE_PATH, O_RDONLY); + + if (fd < 0) { + goto fail; + } + + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { + goto fail; + } + + exit(0); + +fail: + + if (g_dev != nullptr) { + delete g_dev; + g_dev = nullptr; + } + + errx(1, "driver start failed"); +} + +/** + * Stop the driver + */ +void stop() +{ + if (g_dev != nullptr) { + delete g_dev; + g_dev = nullptr; + + } else { + errx(1, "driver not running"); + } + + exit(0); +} + +/** + * Perform some basic functional tests on the driver; + * make sure we can collect data from the sensor in polled + * and automatic modes. + */ +void +test() +{ + struct range_finder_report report; + ssize_t sz; + int ret; + + int fd = open(LL40LS_DEVICE_PATH, O_RDONLY); + + if (fd < 0) { + err(1, "%s open failed (try 'll40ls start' if the driver is not running", LL40LS_DEVICE_PATH); + } + + /* do a simple demand read */ + sz = read(fd, &report, sizeof(report)); + + if (sz != sizeof(report)) { + err(1, "immediate read failed"); + } + + warnx("single read"); + warnx("measurement: %0.2f m", (double)report.distance); + warnx("time: %lld", report.timestamp); + + /* start the sensor polling at 2Hz */ + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, 2)) { + errx(1, "failed to set 2Hz poll rate"); + } + + /* read the sensor 5x and report each value */ + for (unsigned i = 0; i < 5; i++) { + struct pollfd fds; + + /* wait for data to be ready */ + fds.fd = fd; + fds.events = POLLIN; + ret = poll(&fds, 1, 2000); + + if (ret != 1) { + errx(1, "timed out waiting for sensor data"); + } + + /* now go get it */ + sz = read(fd, &report, sizeof(report)); + + if (sz != sizeof(report)) { + err(1, "periodic read failed"); + } + + warnx("periodic read %u", i); + warnx("measurement: %0.3f", (double)report.distance); + warnx("time: %lld", report.timestamp); + } + + /* reset the sensor polling to default rate */ + if (OK != ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT)) { + errx(1, "failed to set default poll rate"); + } + + errx(0, "PASS"); +} + +/** + * Reset the driver. + */ +void +reset() +{ + int fd = open(LL40LS_DEVICE_PATH, O_RDONLY); + + if (fd < 0) { + err(1, "failed "); + } + + if (ioctl(fd, SENSORIOCRESET, 0) < 0) { + err(1, "driver reset failed"); + } + + if (ioctl(fd, SENSORIOCSPOLLRATE, SENSOR_POLLRATE_DEFAULT) < 0) { + err(1, "driver poll restart failed"); + } + + exit(0); +} + +/** + * Print a little info about the driver. + */ +void +info() +{ + if (g_dev == nullptr) { + errx(1, "driver not running"); + } + + printf("state @ %p\n", g_dev); + g_dev->print_info(); + + exit(0); +} + +} // namespace + +int +ll40ls_main(int argc, char *argv[]) +{ + /* + * Start/load the driver. + */ + if (!strcmp(argv[1], "start")) { + ll40ls::start(); + } + + /* + * Stop the driver + */ + if (!strcmp(argv[1], "stop")) { + ll40ls::stop(); + } + + /* + * Test the driver/device. + */ + if (!strcmp(argv[1], "test")) { + ll40ls::test(); + } + + /* + * Reset the driver. + */ + if (!strcmp(argv[1], "reset")) { + ll40ls::reset(); + } + + /* + * Print driver information. + */ + if (!strcmp(argv[1], "info") || !strcmp(argv[1], "status")) { + ll40ls::info(); + } + + errx(1, "unrecognized command, try 'start', 'test', 'reset' or 'info'"); +} diff --git a/src/drivers/ll40ls/module.mk b/src/drivers/ll40ls/module.mk new file mode 100644 index 000000000..ab7d43269 --- /dev/null +++ b/src/drivers/ll40ls/module.mk @@ -0,0 +1,40 @@ +############################################################################ +# +# Copyright (c) 2013 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +# +# Makefile to build the PulsedLight Lidar-Lite driver. +# + +MODULE_COMMAND = ll40ls + +SRCS = ll40ls.cpp -- cgit v1.2.3 From 7f91f0cc3ef806a7959e06ab16d4094bcfe871bd Mon Sep 17 00:00:00 2001 From: akdslr Date: Wed, 30 Apr 2014 14:09:30 -0400 Subject: LL40LS driver: Updated the value to write to the register to trigger a measurement --- src/drivers/ll40ls/ll40ls.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp index cb0eac91b..287207837 100644 --- a/src/drivers/ll40ls/ll40ls.cpp +++ b/src/drivers/ll40ls/ll40ls.cpp @@ -79,7 +79,7 @@ /* LL40LS Registers addresses */ #define LL40LS_MEASURE_REG 0x00 /* Measure range register */ -#define LL40LS_MSRREG_ACQUIRE 0x61 /* Value to initiate a measurement */ +#define LL40LS_MSRREG_ACQUIRE 0x04 /* Value to initiate a measurement, varies based on sensor revision */ #define LL40LS_DISTHIGH_REG 0x8F /* High byte of distance register, auto increment */ /* Device limits */ -- cgit v1.2.3 From 67b7a858881229b95483e986a6e4d90ab34ac257 Mon Sep 17 00:00:00 2001 From: akdslr Date: Thu, 5 Jun 2014 09:53:56 -0400 Subject: LL40LS driver: Changes from the May 4th plane test flight --- src/drivers/ll40ls/ll40ls.cpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp index 287207837..bc012e2e9 100644 --- a/src/drivers/ll40ls/ll40ls.cpp +++ b/src/drivers/ll40ls/ll40ls.cpp @@ -86,7 +86,7 @@ #define LL40LS_MIN_DISTANCE (0.00f) #define LL40LS_MAX_DISTANCE (14.00f) -#define LL40LS_CONVERSION_INTERVAL 60000 /* 60ms */ +#define LL40LS_CONVERSION_INTERVAL 100000 /* 100ms */ /* oddly, ERROR is not defined for c++ */ #ifdef ERROR @@ -517,8 +517,8 @@ LL40LS::collect() return ret; } - uint16_t distance = val[0] << 8 | val[1]; - float si_units = (distance * 1.0f) / 100.0f; /* cm to m */ + uint16_t distance = (val[0] << 8) | val[1]; + float si_units = distance * 0.01f; /* cm to m */ struct range_finder_report report; /* this should be fairly close to the end of the measurement, so the best approximation of the time */ @@ -532,8 +532,10 @@ LL40LS::collect() report.valid = 0; } - /* publish it */ - orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report); + /* publish it, if we are the primary */ + if (_range_finder_topic >= 0) { + orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report); + } if (_reports->force(&report)) { perf_count(_buffer_overflows); -- cgit v1.2.3 From ba54983cdf33b55b47f3b46c9b2461ab7217461a Mon Sep 17 00:00:00 2001 From: akdslr Date: Fri, 6 Jun 2014 08:52:06 -0400 Subject: MB12XX Driver: Added a class instance and device specific path --- src/drivers/mb12xx/mb12xx.cpp | 45 ++++++++++++++++++++++++++++++------------- 1 file changed, 32 insertions(+), 13 deletions(-) diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp index 5adb8cf69..b63e54dac 100644 --- a/src/drivers/mb12xx/mb12xx.cpp +++ b/src/drivers/mb12xx/mb12xx.cpp @@ -74,6 +74,7 @@ /* Configuration Constants */ #define MB12XX_BUS PX4_I2C_BUS_EXPANSION #define MB12XX_BASEADDR 0x70 /* 7-bit address. 8-bit address is 0xE0 */ +#define MB12XX_DEVICE_PATH "/dev/mb12xx" /* MB12xx Registers addresses */ @@ -124,6 +125,7 @@ private: bool _sensor_ok; int _measure_ticks; bool _collect_phase; + int _class_instance; orb_advert_t _range_finder_topic; @@ -187,7 +189,7 @@ private: extern "C" __EXPORT int mb12xx_main(int argc, char *argv[]); MB12XX::MB12XX(int bus, int address) : - I2C("MB12xx", RANGE_FINDER_DEVICE_PATH, bus, address, 100000), + I2C("MB12xx", MB12XX_DEVICE_PATH, bus, address, 100000), _min_distance(MB12XX_MIN_DISTANCE), _max_distance(MB12XX_MAX_DISTANCE), _reports(nullptr), @@ -195,6 +197,7 @@ MB12XX::MB12XX(int bus, int address) : _measure_ticks(0), _collect_phase(false), _range_finder_topic(-1), + _class_instance(-1), _sample_perf(perf_alloc(PC_ELAPSED, "mb12xx_read")), _comms_errors(perf_alloc(PC_COUNT, "mb12xx_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "mb12xx_buffer_overflows")) @@ -215,6 +218,15 @@ MB12XX::~MB12XX() if (_reports != nullptr) { delete _reports; } + + if (_class_instance != -1) { + unregister_class_devname(RANGE_FINDER_DEVICE_PATH, _class_instance); + } + + // free perf counters + perf_free(_sample_perf); + perf_free(_comms_errors); + perf_free(_buffer_overflows); } int @@ -234,13 +246,18 @@ MB12XX::init() goto out; } - /* get a publish handle on the range finder topic */ - struct range_finder_report zero_report; - memset(&zero_report, 0, sizeof(zero_report)); - _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &zero_report); + _class_instance = register_class_devname(RANGE_FINDER_DEVICE_PATH); - if (_range_finder_topic < 0) { - debug("failed to create sensor_range_finder object. Did you start uOrb?"); + if (_class_instance == CLASS_DEVICE_PRIMARY) { + /* get a publish handle on the range finder topic */ + struct range_finder_report rf_report; + measure(); + _reports->get(&rf_report); + _range_finder_topic = orb_advertise(ORB_ID(sensor_range_finder), &rf_report); + + if (_range_finder_topic < 0) { + debug("failed to create sensor_range_finder object. Did you start uOrb?"); + } } ret = OK; @@ -505,8 +522,10 @@ MB12XX::collect() report.distance = si_units; report.valid = si_units > get_minimum_distance() && si_units < get_maximum_distance() ? 1 : 0; - /* publish it */ - orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report); + /* publish it, if we are the primary */ + if (_range_finder_topic >= 0) { + orb_publish(ORB_ID(sensor_range_finder), _range_finder_topic, &report); + } if (_reports->force(&report)) { perf_count(_buffer_overflows); @@ -665,7 +684,7 @@ start() } /* set the poll rate to default, starts automatic data collection */ - fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY); + fd = open(MB12XX_DEVICE_PATH, O_RDONLY); if (fd < 0) { goto fail; @@ -715,10 +734,10 @@ test() ssize_t sz; int ret; - int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY); + int fd = open(MB12XX_DEVICE_PATH, O_RDONLY); if (fd < 0) { - err(1, "%s open failed (try 'mb12xx start' if the driver is not running", RANGE_FINDER_DEVICE_PATH); + err(1, "%s open failed (try 'mb12xx start' if the driver is not running", MB12XX_DEVICE_PATH); } /* do a simple demand read */ @@ -776,7 +795,7 @@ test() void reset() { - int fd = open(RANGE_FINDER_DEVICE_PATH, O_RDONLY); + int fd = open(MB12XX_DEVICE_PATH, O_RDONLY); if (fd < 0) { err(1, "failed "); -- cgit v1.2.3 From 681d746e060cbd82008967ea56dc950c9ca7ef49 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 8 Jul 2014 13:21:08 +0200 Subject: update mavlink to latest master --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 3711190d2..d1ebe85eb 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 3711190d23d9928ea0687e00621c8d9ecf145f50 +Subproject commit d1ebe85eb6bb06d0078f3e0b8144adb131263628 -- cgit v1.2.3 From a6b52f1c9f720a8dd31099e7adeedee694f60729 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:49:24 +0200 Subject: HMC5883 post merge cleanup --- src/drivers/device/spi.cpp | 4 ++-- src/drivers/hmc5883/hmc5883.cpp | 3 ++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp index fed6c312c..0b232e158 100644 --- a/src/drivers/device/spi.cpp +++ b/src/drivers/device/spi.cpp @@ -69,11 +69,11 @@ SPI::SPI(const char *name, // protected locking_mode(LOCK_PREEMPTION), // private - _bus(bus), _device(device), _mode(mode), _frequency(frequency), - _dev(nullptr) + _dev(nullptr), + _bus(bus) { } diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 72d6bdd95..c2e4700d8 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1266,7 +1266,7 @@ int calibrate(int bus); * Start the driver. */ void -start(enum Rotation rotation) +start(int bus, enum Rotation rotation) { int fd; @@ -1528,6 +1528,7 @@ int hmc5883_main(int argc, char *argv[]) { int ch; + int bus = -1; enum Rotation rotation = ROTATION_NONE; bool calibrate = false; -- cgit v1.2.3 From 369c7d277f2fea351ca4243debccc0a115f3f7e4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:50:00 +0200 Subject: Board config cleanup for external bus support --- makefiles/config_px4fmu-v2_test.mk | 1 + src/drivers/boards/px4fmu-v1/board_config.h | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/config_px4fmu-v2_test.mk b/makefiles/config_px4fmu-v2_test.mk index 66d9efbf8..395a8f2ac 100644 --- a/makefiles/config_px4fmu-v2_test.mk +++ b/makefiles/config_px4fmu-v2_test.mk @@ -42,6 +42,7 @@ MODULES += modules/uORB LIBRARIES += lib/mathlib/CMSIS MODULES += lib/mathlib MODULES += lib/mathlib/math/filter +MODULES += lib/conversion # # Libraries diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h index c944007a5..a70a6240c 100644 --- a/src/drivers/boards/px4fmu-v1/board_config.h +++ b/src/drivers/boards/px4fmu-v1/board_config.h @@ -86,7 +86,6 @@ __BEGIN_DECLS #define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4) #define PX4_SPI_BUS_SENSORS 1 -#define PX4_SPI_BUS_EXT 2 /* * Use these in place of the spi_dev_e enumeration to -- cgit v1.2.3 From a42ec7df1b417a34e072a68c6e34240a97d5ba80 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:50:24 +0200 Subject: MS5611: Deal with missing external bus --- src/drivers/ms5611/ms5611_spi.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/drivers/ms5611/ms5611_spi.cpp b/src/drivers/ms5611/ms5611_spi.cpp index 00d016aed..5234ce8d6 100644 --- a/src/drivers/ms5611/ms5611_spi.cpp +++ b/src/drivers/ms5611/ms5611_spi.cpp @@ -118,7 +118,11 @@ device::Device * MS5611_spi_interface(ms5611::prom_u &prom_buf, bool external_bus) { if (external_bus) { + #ifdef PX4_SPI_BUS_EXT return new MS5611_SPI(PX4_SPI_BUS_EXT, (spi_dev_e)PX4_SPIDEV_EXT_BARO, prom_buf); + #else + return nullptr; + #endif } else { return new MS5611_SPI(PX4_SPI_BUS_SENSORS, (spi_dev_e)PX4_SPIDEV_BARO, prom_buf); } -- cgit v1.2.3 From 92426c5cfc8e9746fe42e4c9c087a5e25a4be658 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:51:33 +0200 Subject: LSM303D: deal with missing external bus --- src/drivers/lsm303d/lsm303d.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index f25ac8f87..296899ccd 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -1810,10 +1810,15 @@ start(bool external_bus, enum Rotation rotation) /* create the driver */ if (external_bus) { + #ifdef PX4_SPI_BUS_EXT g_dev = new LSM303D(PX4_SPI_BUS_EXT, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_EXT_ACCEL_MAG, rotation); + #else + errx(0, "External SPI not available"); + #endif } else { g_dev = new LSM303D(PX4_SPI_BUS_SENSORS, LSM303D_DEVICE_PATH_ACCEL, (spi_dev_e)PX4_SPIDEV_ACCEL_MAG, rotation); } + if (g_dev == nullptr) { warnx("failed instantiating LSM303D obj"); goto fail; -- cgit v1.2.3 From 7d15e999f12fcfa7650c673e8be1daffbbfc46d2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:52:10 +0200 Subject: LSM303: Fix usage function call to fit existing structure. --- src/drivers/lsm303d/lsm303d.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 296899ccd..7ba0fcc88 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -1797,6 +1797,7 @@ void reset(); void info(); void regdump(); void logging(); +void usage(); /** * Start the driver. @@ -2013,17 +2014,17 @@ logging() exit(0); } - -} // namespace - void -lsm303d_usage() +usage() { warnx("missing command: try 'start', 'info', 'test', 'reset', 'regdump', 'logging'"); warnx("options:"); warnx(" -X (external bus)"); + warnx(" -R rotation"); } +} // namespace + int lsm303d_main(int argc, char *argv[]) { @@ -2041,7 +2042,7 @@ lsm303d_main(int argc, char *argv[]) rotation = (enum Rotation)atoi(optarg); break; default: - lsm303d_usage(); + lsm303d::usage(); exit(0); } } -- cgit v1.2.3 From 875be65242dc58503c44ff522372b3cc2df83619 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:52:28 +0200 Subject: MPU6000: Fix usage function call to fit existing structure. --- src/drivers/mpu6000/mpu6000.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index f6e00feee..5668b0865 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -1433,6 +1433,7 @@ void start(bool, enum Rotation); void test(bool); void reset(bool); void info(bool); +void usage(); /** * Start the driver. @@ -1604,17 +1605,17 @@ info(bool external_bus) exit(0); } - -} // namespace - void -mpu6000_usage() +usage() { warnx("missing command: try 'start', 'info', 'test', 'reset'"); warnx("options:"); warnx(" -X (external bus)"); + warnx(" -R rotation"); } +} // namespace + int mpu6000_main(int argc, char *argv[]) { @@ -1632,7 +1633,7 @@ mpu6000_main(int argc, char *argv[]) rotation = (enum Rotation)atoi(optarg); break; default: - mpu6000_usage(); + mpu6000::usage(); exit(0); } } -- cgit v1.2.3 From 812d326912feb41bb37848d61b1a6e6e1d18ab90 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:52:42 +0200 Subject: L3GD20: Fix usage function call to fit existing structure. --- src/drivers/l3gd20/l3gd20.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index cad3ff937..64d1a7e55 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -982,7 +982,7 @@ namespace l3gd20 L3GD20 *g_dev; -void l3gd20_usage(); +void usage(); void start(bool external_bus, enum Rotation rotation); void test(); void reset(); @@ -1120,17 +1120,17 @@ info() exit(0); } - -} // namespace - void -l3gd20_usage() +usage() { warnx("missing command: try 'start', 'info', 'test', 'reset'"); warnx("options:"); warnx(" -X (external bus)"); + warnx(" -R rotation"); } +} // namespace + int l3gd20_main(int argc, char *argv[]) { @@ -1148,7 +1148,7 @@ l3gd20_main(int argc, char *argv[]) rotation = (enum Rotation)atoi(optarg); break; default: - l3gd20_usage(); + l3gd20::usage(); exit(0); } } -- cgit v1.2.3 From f2cbc7fe2778b4148bdecd59148ec96b84a248df Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:53:10 +0200 Subject: MB12xx: Fix initialiser order in class --- src/drivers/mb12xx/mb12xx.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/mb12xx/mb12xx.cpp b/src/drivers/mb12xx/mb12xx.cpp index b63e54dac..beb6c8e35 100644 --- a/src/drivers/mb12xx/mb12xx.cpp +++ b/src/drivers/mb12xx/mb12xx.cpp @@ -196,8 +196,8 @@ MB12XX::MB12XX(int bus, int address) : _sensor_ok(false), _measure_ticks(0), _collect_phase(false), - _range_finder_topic(-1), _class_instance(-1), + _range_finder_topic(-1), _sample_perf(perf_alloc(PC_ELAPSED, "mb12xx_read")), _comms_errors(perf_alloc(PC_COUNT, "mb12xx_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "mb12xx_buffer_overflows")) -- cgit v1.2.3 From 83f343f196c07d0a633ee8fc7d2324e8cb3d129c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:53:25 +0200 Subject: LL40LS: Fix initialiser order in class --- src/drivers/ll40ls/ll40ls.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/ll40ls/ll40ls.cpp b/src/drivers/ll40ls/ll40ls.cpp index bc012e2e9..a69e6ee55 100644 --- a/src/drivers/ll40ls/ll40ls.cpp +++ b/src/drivers/ll40ls/ll40ls.cpp @@ -196,8 +196,8 @@ LL40LS::LL40LS(int bus, int address) : _sensor_ok(false), _measure_ticks(0), _collect_phase(false), - _range_finder_topic(-1), _class_instance(-1), + _range_finder_topic(-1), _sample_perf(perf_alloc(PC_ELAPSED, "ll40ls_read")), _comms_errors(perf_alloc(PC_COUNT, "ll40ls_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "ll40ls_buffer_overflows")) -- cgit v1.2.3 From ea4de4adc388e9353114e6e2c89eb27cec5b249e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:54:01 +0200 Subject: param command: fix warnings --- src/systemcmds/param/param.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/systemcmds/param/param.c b/src/systemcmds/param/param.c index 28e1b108b..e110335e7 100644 --- a/src/systemcmds/param/param.c +++ b/src/systemcmds/param/param.c @@ -63,7 +63,7 @@ static void do_import(const char* param_file_name); static void do_show(const char* search_string); static void do_show_print(void *arg, param_t param); static void do_set(const char* name, const char* val, bool fail_on_not_found); -static void do_compare(const char* name, const char* vals[], unsigned comparisons); +static void do_compare(const char* name, char* vals[], unsigned comparisons); static void do_reset(void); static void do_reset_nostart(void); @@ -351,7 +351,7 @@ do_set(const char* name, const char* val, bool fail_on_not_found) } static void -do_compare(const char* name, const char* vals[], unsigned comparisons) +do_compare(const char* name, char* vals[], unsigned comparisons) { int32_t i; float f; -- cgit v1.2.3 From e380aa3f62c9db89f048f3683e3611e455de4ad2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 13:54:33 +0200 Subject: AT24C: Fix warning due to missing function prototype. --- src/systemcmds/mtd/24xxxx_mtd.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/systemcmds/mtd/24xxxx_mtd.c b/src/systemcmds/mtd/24xxxx_mtd.c index 72200f418..991363797 100644 --- a/src/systemcmds/mtd/24xxxx_mtd.c +++ b/src/systemcmds/mtd/24xxxx_mtd.c @@ -161,6 +161,7 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, static int at24c_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg); void at24c_test(void); +int at24c_nuke(void); /************************************************************************************ * Private Data -- cgit v1.2.3 From ac8f179f2dad99d664a6f9de4df954bea7fe5858 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Jul 2014 20:24:18 +1000 Subject: Tools: skip check_submodules.sh when NUTTX_SRC is set this avoids using submodules when a specific NuttX tree is specified --- Tools/check_submodules.sh | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index fb180ef47..4b8789b28 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -1,5 +1,12 @@ #!/bin/sh +[ -n "$NUTTX_SRC" ] && { + # NUTTX_SRC is set, meaning user is overriding the NuttX tree to use. Don't + # use submodules to pull an alternatiie tree + echo "Skipping submodules as NUTTX_SRC is set to $NUTTX_SRC" + exit 0 +} + if [ -d NuttX/nuttx ]; then STATUSRETVAL=$(git status --porcelain | grep -i "NuttX") -- cgit v1.2.3 From 52713bc0ba891854934f62ad856f1600e8ba3065 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 15:00:44 +0200 Subject: Revert "Tools: skip check_submodules.sh when NUTTX_SRC is set" This reverts commit ac8f179f2dad99d664a6f9de4df954bea7fe5858. --- Tools/check_submodules.sh | 7 ------- 1 file changed, 7 deletions(-) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index 4b8789b28..fb180ef47 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -1,12 +1,5 @@ #!/bin/sh -[ -n "$NUTTX_SRC" ] && { - # NUTTX_SRC is set, meaning user is overriding the NuttX tree to use. Don't - # use submodules to pull an alternatiie tree - echo "Skipping submodules as NUTTX_SRC is set to $NUTTX_SRC" - exit 0 -} - if [ -d NuttX/nuttx ]; then STATUSRETVAL=$(git status --porcelain | grep -i "NuttX") -- cgit v1.2.3 From bc06d839eab504e039c27cd472bbd1162cb7bbf4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Jul 2014 20:24:18 +1000 Subject: Tools: skip check_submodules.sh when GIT_SUBMODULES_ARE_EVIL is set this avoids using submodules when a specific NuttX tree is specified --- Tools/check_submodules.sh | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index fb180ef47..55bcc05ee 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -1,5 +1,11 @@ #!/bin/sh +[ -n "$GIT_SUBMODULES_ARE_EVIL" ] && { + # GIT_SUBMODULES_ARE_EVIL is set, meaning user doesn't want submodules + echo "Skipping submodules. NUTTX_SRC is set to $NUTTX_SRC" + exit 0 +} + if [ -d NuttX/nuttx ]; then STATUSRETVAL=$(git status --porcelain | grep -i "NuttX") -- cgit v1.2.3 From 76f82bf237de367a3a3b214f2ba06faddb077c57 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 15:04:01 +0200 Subject: Updated submodule update instructions --- Tools/check_submodules.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index 55bcc05ee..7c3a3bfc2 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -12,7 +12,7 @@ if [ -d NuttX/nuttx ]; if [ "$STATUSRETVAL" == "" ]; then echo "Checked NuttX submodule, correct version found" else - echo "NuttX sub repo not at correct version. Try 'make updatesubmodules'" + echo "NuttX sub repo not at correct version. Try 'git submodule update'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" exit 1 fi @@ -28,7 +28,7 @@ if [ -d mavlink/include/mavlink/v1.0 ]; if [ "$STATUSRETVAL" == "" ]; then echo "Checked mavlink submodule, correct version found" else - echo "mavlink sub repo not at correct version. Try 'make updatesubmodules'" + echo "mavlink sub repo not at correct version. Try 'git submodule update'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" exit 1 fi -- cgit v1.2.3 From ee9233451244604f1522dda5e58d1deb7ec6473d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Jul 2014 20:23:07 +1000 Subject: build: fixed running build from external directory --- Makefile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 8bf96ca23..7b7c00704 100644 --- a/Makefile +++ b/Makefile @@ -210,11 +210,11 @@ menuconfig: endif $(NUTTX_SRC): - $(Q) (./Tools/check_submodules.sh) + $(Q) ($(PX4_BASE)/Tools/check_submodules.sh) .PHONY: checksubmodules checksubmodules: - $(Q) (./Tools/check_submodules.sh) + $(Q) ($(PX4_BASE)/Tools/check_submodules.sh) .PHONY: updatesubmodules updatesubmodules: -- cgit v1.2.3 From 0054eb23d857844ebae34a7d198fc60e538ccd3c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 8 Jul 2014 15:44:22 +0200 Subject: Update sensors tests --- src/systemcmds/tests/test_sensors.c | 37 ++++++++++++++++++++++++++++++++++++- 1 file changed, 36 insertions(+), 1 deletion(-) diff --git a/src/systemcmds/tests/test_sensors.c b/src/systemcmds/tests/test_sensors.c index 096106ff3..a4f17eebd 100644 --- a/src/systemcmds/tests/test_sensors.c +++ b/src/systemcmds/tests/test_sensors.c @@ -139,7 +139,14 @@ accel(int argc, char *argv[]) } if (fabsf(buf.x) > 30.0f || fabsf(buf.y) > 30.0f || fabsf(buf.z) > 30.0f) { - warnx("ACCEL1 acceleration values out of range!"); + warnx("ACCEL acceleration values out of range!"); + return ERROR; + } + + float len = sqrtf(buf.x * buf.x + buf.y * buf.y + buf.z * buf.z); + + if (len < 8.0f || len > 12.0f) { + warnx("ACCEL scale error!"); return ERROR; } @@ -186,6 +193,13 @@ accel1(int argc, char *argv[]) return ERROR; } + float len = sqrtf(buf.x * buf.x + buf.y * buf.y + buf.z * buf.z); + + if (len < 8.0f || len > 12.0f) { + warnx("ACCEL1 scale error!"); + return ERROR; + } + /* Let user know everything is ok */ printf("\tOK: ACCEL1 passed all tests successfully\n"); @@ -225,6 +239,13 @@ gyro(int argc, char *argv[]) printf("\tGYRO rates: x:%8.4f\ty:%8.4f\tz:%8.4f rad/s\n", (double)buf.x, (double)buf.y, (double)buf.z); } + float len = sqrtf(buf.x * buf.x + buf.y * buf.y + buf.z * buf.z); + + if (len > 0.3f) { + warnx("GYRO scale error!"); + return ERROR; + } + /* Let user know everything is ok */ printf("\tOK: GYRO passed all tests successfully\n"); close(fd); @@ -263,6 +284,13 @@ gyro1(int argc, char *argv[]) printf("\tGYRO1 rates: x:%8.4f\ty:%8.4f\tz:%8.4f rad/s\n", (double)buf.x, (double)buf.y, (double)buf.z); } + float len = sqrtf(buf.x * buf.x + buf.y * buf.y + buf.z * buf.z); + + if (len > 0.3f) { + warnx("GYRO1 scale error!"); + return ERROR; + } + /* Let user know everything is ok */ printf("\tOK: GYRO1 passed all tests successfully\n"); close(fd); @@ -301,6 +329,13 @@ mag(int argc, char *argv[]) printf("\tMAG values: x:%8.4f\ty:%8.4f\tz:%8.4f\n", (double)buf.x, (double)buf.y, (double)buf.z); } + float len = sqrtf(buf.x * buf.x + buf.y * buf.y + buf.z * buf.z); + + if (len < 1.0f || len > 3.0f) { + warnx("MAG scale error!"); + return ERROR; + } + /* Let user know everything is ok */ printf("\tOK: MAG passed all tests successfully\n"); close(fd); -- cgit v1.2.3 From 6814ddccffd6f9f5a208ad87ffb5aa4045ba8543 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 8 Jul 2014 20:19:17 +0400 Subject: UAVCAN as a submodule --- .gitignore | 1 - .gitmodules | 3 +++ Makefile | 3 +++ Tools/check_submodules.sh | 16 ++++++++++++++++ uavcan | 1 + 5 files changed, 23 insertions(+), 1 deletion(-) create mode 160000 uavcan diff --git a/.gitignore b/.gitignore index d0c624543..8b09e4783 100644 --- a/.gitignore +++ b/.gitignore @@ -36,6 +36,5 @@ mavlink/include/mavlink/v0.9/ tags .tags_sorted_by_file .pydevproject -/uavcan .ropeproject *.orig diff --git a/.gitmodules b/.gitmodules index 8436b398e..4b84afac2 100644 --- a/.gitmodules +++ b/.gitmodules @@ -4,3 +4,6 @@ [submodule "NuttX"] path = NuttX url = git://github.com/PX4/NuttX.git +[submodule "uavcan"] + path = uavcan + url = git://github.com/pavel-kirienko/uavcan.git diff --git a/Makefile b/Makefile index 8bf96ca23..e2d50e8fc 100644 --- a/Makefile +++ b/Makefile @@ -212,6 +212,9 @@ endif $(NUTTX_SRC): $(Q) (./Tools/check_submodules.sh) +$(UAVCAN_DIR): + $(Q) (./Tools/check_submodules.sh) + .PHONY: checksubmodules checksubmodules: $(Q) (./Tools/check_submodules.sh) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index fb180ef47..a178b4a38 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -31,4 +31,20 @@ else git submodule update; fi + +if [ -d uavcan/libuavcan_drivers ]; +then + STATUSRETVAL=$(git status --porcelain | grep -i uavcan) + if [ "$STATUSRETVAL" == "" ]; then + echo "Checked uavcan submodule, correct version found" + else + echo "uavcan sub repo not at correct version. Try 'make updatesubmodules'" + echo "or follow instructions on http://pixhawk.org/dev/git/submodules" + exit 1 + fi +else + git submodule init + git submodule update +fi + exit 0 diff --git a/uavcan b/uavcan new file mode 160000 index 000000000..f66c1a7de --- /dev/null +++ b/uavcan @@ -0,0 +1 @@ +Subproject commit f66c1a7de3076ff956bdf159dc3a166cbffe6089 -- cgit v1.2.3 From b4ab31a2bac2b069528d56740901b3d69d2f2227 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 8 Jul 2014 19:11:28 +0200 Subject: A more compatible way of checking for an empty string. --- Tools/check_submodules.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index fb180ef47..086b6f35d 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -3,7 +3,7 @@ if [ -d NuttX/nuttx ]; then STATUSRETVAL=$(git status --porcelain | grep -i "NuttX") - if [ "$STATUSRETVAL" == "" ]; then + if [ -z $STATUSRETVAL ]; then echo "Checked NuttX submodule, correct version found" else echo "NuttX sub repo not at correct version. Try 'make updatesubmodules'" @@ -19,7 +19,7 @@ fi if [ -d mavlink/include/mavlink/v1.0 ]; then STATUSRETVAL=$(git status --porcelain | grep -i "mavlink/include/mavlink/v1.0") - if [ "$STATUSRETVAL" == "" ]; then + if [ -z $STATUSRETVAL ]; then echo "Checked mavlink submodule, correct version found" else echo "mavlink sub repo not at correct version. Try 'make updatesubmodules'" -- cgit v1.2.3 From 13b41a2629ddf964951eb228534c5a9680a0f100 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 8 Jul 2014 19:17:25 +0200 Subject: Add quotes around the variable. It's safer. --- Tools/check_submodules.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index 086b6f35d..db81ed04a 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -3,7 +3,7 @@ if [ -d NuttX/nuttx ]; then STATUSRETVAL=$(git status --porcelain | grep -i "NuttX") - if [ -z $STATUSRETVAL ]; then + if [ -z "$STATUSRETVAL" ]; then echo "Checked NuttX submodule, correct version found" else echo "NuttX sub repo not at correct version. Try 'make updatesubmodules'" @@ -19,7 +19,7 @@ fi if [ -d mavlink/include/mavlink/v1.0 ]; then STATUSRETVAL=$(git status --porcelain | grep -i "mavlink/include/mavlink/v1.0") - if [ -z $STATUSRETVAL ]; then + if [ -z "$STATUSRETVAL" ]; then echo "Checked mavlink submodule, correct version found" else echo "mavlink sub repo not at correct version. Try 'make updatesubmodules'" -- cgit v1.2.3 From c39e572a063b8e17c2c8f896fdae4d0ec159960f Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 8 Jul 2014 23:58:16 +0200 Subject: Updated the Wing Wing params based on latest flight tests. --- ROMFS/px4fmu_common/init.d/3033_wingwing | 27 +++++++++++++++++++-------- 1 file changed, 19 insertions(+), 8 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing index fff4b58df..765685ccc 100644 --- a/ROMFS/px4fmu_common/init.d/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/3033_wingwing @@ -11,25 +11,36 @@ if [ $DO_AUTOCONFIG == yes ] then param set BAT_N_CELLS 2 param set FW_AIRSPD_MAX 15 - param set FW_AIRSPD_MIN 7 - param set FW_AIRSPD_TRIM 11 + param set FW_AIRSPD_MIN 10 + param set FW_AIRSPD_TRIM 13 param set FW_ATT_TC 0.3 param set FW_L1_DAMPING 0.74 - param set FW_L1_PERIOD 12 + param set FW_L1_PERIOD 16 param set FW_LND_ANG 15 param set FW_LND_FLALT 5 param set FW_LND_HHDIST 15 param set FW_LND_HVIRT 13 param set FW_LND_TLALT 5 param set FW_THR_LND_MAX 0 - param set FW_P_ROLLFF 2 - param set FW_PR_FF 0.6 - param set FW_PR_IMAX 0.2 - param set FW_PR_P 0.06 + param set FW_PR_FF 0.35 + param set FW_PR_I 0.005 + param set FW_PR_IMAX 0.4 + param set FW_PR_P 0.08 param set FW_RR_FF 0.6 + param set FW_RR_I 0.005 param set FW_RR_IMAX 0.2 - param set FW_RR_P 0.09 + param set FW_RR_P 0.04 param set FW_THR_CRUISE 0.65 + param set MT_TKF_PIT_MAX 30.0 + param set MT_ACC_D 0.2 + param set MT_ACC_P 0.6 + param set MT_A_LP 0.5 + param set MT_PIT_OFF 0.1 + param set MT_PIT_I 0.1 + param set MT_THR_OFF 0.12 + param set MT_THR_I 0.35 + param set MT_THR_P 0.2 + param set MT_THR_FF 1.5 fi set MIXER FMU_Q -- cgit v1.2.3 From 8c6745d53fcb75c14caa21f3cb917ab6fa5f2bcf Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Thu, 10 Jul 2014 00:41:09 -0400 Subject: Prevent stack overflow when flashing px4io Large local variable causing stack overflow when attempting to flash IO!!! --- src/drivers/px4io/px4io_uploader.cpp | 18 +++++++++++++++--- 1 file changed, 15 insertions(+), 3 deletions(-) diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp index 7b6361a7c..652949e41 100644 --- a/src/drivers/px4io/px4io_uploader.cpp +++ b/src/drivers/px4io/px4io_uploader.cpp @@ -39,6 +39,7 @@ #include #include +#include #include #include #include @@ -413,11 +414,17 @@ static int read_with_retry(int fd, void *buf, size_t n) int PX4IO_Uploader::program(size_t fw_size) { - uint8_t file_buf[PROG_MULTI_MAX]; + uint8_t *file_buf; ssize_t count; int ret; size_t sent = 0; + file_buf = (uint8_t *)malloc(PROG_MULTI_MAX); + if (!file_buf) { + log("Can't allocate program buffer"); + return -ENOMEM; + } + log("programming %u bytes...", (unsigned)fw_size); ret = lseek(_fw_fd, 0, SEEK_SET); @@ -438,8 +445,10 @@ PX4IO_Uploader::program(size_t fw_size) (int)errno); } - if (count == 0) + if (count == 0) { + free(file_buf); return OK; + } sent += count; @@ -455,9 +464,12 @@ PX4IO_Uploader::program(size_t fw_size) ret = get_sync(1000); - if (ret != OK) + if (ret != OK) { + free(file_buf); return ret; + } } + free(file_buf); return OK; } -- cgit v1.2.3 From 12da0efbb24ad135dbacb4b8f90199b3b38cb40d Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Thu, 10 Jul 2014 00:55:33 -0400 Subject: Read the full buffer sizeof wont work here since file_buf is now a pointer --- src/drivers/px4io/px4io_uploader.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp index 652949e41..d134c0246 100644 --- a/src/drivers/px4io/px4io_uploader.cpp +++ b/src/drivers/px4io/px4io_uploader.cpp @@ -432,8 +432,8 @@ PX4IO_Uploader::program(size_t fw_size) while (sent < fw_size) { /* get more bytes to program */ size_t n = fw_size - sent; - if (n > sizeof(file_buf)) { - n = sizeof(file_buf); + if (n > PROG_MULTI_MAX) { + n = PROG_MULTI_MAX; } count = read_with_retry(_fw_fd, file_buf, n); -- cgit v1.2.3 From 9b2d444cc56eaaedcf271f200b93dcca94623209 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 10 Jul 2014 14:08:09 +0200 Subject: dataman: use DM_KEY_WAYPOINTS_OFFBOARD() macro everywhere --- src/modules/mavlink/mavlink_mission.cpp | 4 ++-- src/modules/navigator/mission.cpp | 23 +++++------------------ 2 files changed, 7 insertions(+), 20 deletions(-) diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index b2288469c..0dda2337e 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -216,7 +216,7 @@ MavlinkMissionManager::send_mission_count(uint8_t sysid, uint8_t compid, uint16_ void MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t seq) { - dm_item_t dm_item = _dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; + dm_item_t dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_dataman_id); struct mission_item_s mission_item; if (dm_read(dm_item, seq, &mission_item, sizeof(struct mission_item_s)) == sizeof(struct mission_item_s)) { @@ -650,7 +650,7 @@ MavlinkMissionManager::handle_mission_item(const mavlink_message_t *msg) return; } - dm_item_t dm_item = _transfer_dataman_id == 0 ? DM_KEY_WAYPOINTS_OFFBOARD_0 : DM_KEY_WAYPOINTS_OFFBOARD_1; + dm_item_t dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_transfer_dataman_id); if (dm_write(dm_item, wp.seq, DM_PERSIST_POWER_ON_RESET, &mission_item, sizeof(struct mission_item_s)) != sizeof(struct mission_item_s)) { if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _transfer_dataman_id); } diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 53f0724cd..06e915f27 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -201,19 +201,11 @@ Mission::update_offboard_mission() /* Check mission feasibility, for now do not handle the return value, * however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */ - dm_item_t dm_current; + dm_item_t dm_current = DM_KEY_WAYPOINTS_OFFBOARD(_transfer_dataman_id); - if (_offboard_mission.dataman_id == 0) { - dm_current = DM_KEY_WAYPOINTS_OFFBOARD_0; - - } else { - dm_current = DM_KEY_WAYPOINTS_OFFBOARD_1; - } - - missionFeasiblityChecker.checkMissionFeasible(_navigator->get_vstatus()->is_rotary_wing, dm_current, - (size_t)_offboard_mission.count, - _navigator->get_geofence(), - _navigator->get_home_position()->alt); + missionFeasiblityChecker.checkMissionFeasible(_navigator->get_vstatus()->is_rotary_wing, + dm_current, (size_t) _offboard_mission.count, _navigator->get_geofence(), + _navigator->get_home_position()->alt); } else { warnx("offboard mission update failed"); @@ -474,12 +466,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s mission = &_offboard_mission; - if (_offboard_mission.dataman_id == 0) { - dm_item = DM_KEY_WAYPOINTS_OFFBOARD_0; - - } else { - dm_item = DM_KEY_WAYPOINTS_OFFBOARD_1; - } + dm_item = DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id); } if (*mission_index_ptr < 0 || *mission_index_ptr >= (int)mission->count) { -- cgit v1.2.3 From bc602ff1e2c2ab6c08a7d5edf0b1f03308e011f8 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 10 Jul 2014 14:38:38 +0200 Subject: mavlink submodule fixed --- mavlink/include/mavlink/v1.0 | 1 + 1 file changed, 1 insertion(+) create mode 160000 mavlink/include/mavlink/v1.0 diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 new file mode 160000 index 000000000..d1ebe85eb --- /dev/null +++ b/mavlink/include/mavlink/v1.0 @@ -0,0 +1 @@ +Subproject commit d1ebe85eb6bb06d0078f3e0b8144adb131263628 -- cgit v1.2.3 From 3157b06fee99b57fe336f7772b293f8689ff8cdf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 10 Jul 2014 15:52:19 +0200 Subject: Generalized the airspeed check --- src/modules/commander/state_machine_helper.cpp | 29 ++++++++++---------------- 1 file changed, 11 insertions(+), 18 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 6b96e3a3f..d894c9db0 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -52,6 +52,7 @@ #include #include #include +#include #include #include #include @@ -666,29 +667,21 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) } if (!status->is_rotary_wing) { - fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); - if (fd < 0) { + fd = orb_subscribe(ORB_ID(airspeed)); + + struct airspeed_s airspeed; + + if (ret = orb_copy(ORB_ID(airspeed), fd, &airspeed) || + hrt_elapsed_time(&airspeed.timestamp) > 50 * 1000) { mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED SENSOR MISSING"); - ret = fd; goto system_eval; } - struct differential_pressure_s diff_pres; - - ret = read(fd, &diff_pres, sizeof(diff_pres)); - - if (ret == sizeof(diff_pres)) { - if (fabsf(diff_pres.differential_pressure_filtered_pa > 5.0f)) { - mavlink_log_critical(mavlink_fd, "#audio: WARNING AIRSPEED CALIBRATION MISSING"); - // XXX do not make this fatal yet - ret = OK; - } - } else { - mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED READ"); - /* this is frickin' fatal */ - ret = ERROR; - goto system_eval; + if (fabsf(airspeed.indicated_airspeed_m_s > 5.0f)) { + mavlink_log_critical(mavlink_fd, "#audio: WARNING AIRSPEED CALIBRATION MISSING"); + // XXX do not make this fatal yet + ret = OK; } } -- cgit v1.2.3 From 5bb8c501122de7daece58c5770b6aca13c0066cd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 10 Jul 2014 16:14:21 +0200 Subject: Fixed the submodule check logic --- Tools/check_submodules.sh | 22 ++++++++++++++++++---- 1 file changed, 18 insertions(+), 4 deletions(-) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index db81ed04a..a56de681f 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -2,12 +2,19 @@ if [ -d NuttX/nuttx ]; then - STATUSRETVAL=$(git status --porcelain | grep -i "NuttX") + STATUSRETVAL=$(git submodule summary | grep -A20 -i "NuttX" | grep "<") if [ -z "$STATUSRETVAL" ]; then echo "Checked NuttX submodule, correct version found" else - echo "NuttX sub repo not at correct version. Try 'make updatesubmodules'" + echo "" + echo "" + echo "NuttX sub repo not at correct version. Try 'git submodule update'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" + echo "" + echo "" + echo "New commits required:" + echo "$(git submodule summary)" + echo "" exit 1 fi else @@ -18,12 +25,19 @@ fi if [ -d mavlink/include/mavlink/v1.0 ]; then - STATUSRETVAL=$(git status --porcelain | grep -i "mavlink/include/mavlink/v1.0") + STATUSRETVAL=$(git submodule summary | grep -A20 -i "mavlink/include/mavlink/v1.0" | grep "<") if [ -z "$STATUSRETVAL" ]; then echo "Checked mavlink submodule, correct version found" else - echo "mavlink sub repo not at correct version. Try 'make updatesubmodules'" + echo "" + echo "" + echo "mavlink sub repo not at correct version. Try 'git submodule update'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" + echo "" + echo "" + echo "New commits required:" + echo "$(git submodule summary)" + echo "" exit 1 fi else -- cgit v1.2.3 From e57579fa21ce9be189475e41fbcdb961d7cd32d2 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 10 Jul 2014 17:08:23 +0200 Subject: mavlink, navigator: compile errors/warnings fixed --- src/modules/mavlink/mavlink_main.cpp | 4 ++-- src/modules/mavlink/mavlink_mission.cpp | 2 +- src/modules/navigator/mission.cpp | 12 ++++-------- 3 files changed, 7 insertions(+), 11 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 5c7eefa98..0d685c3d8 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -226,8 +226,9 @@ Mavlink::Mavlink() : _main_loop_delay(1000), _subscriptions(nullptr), _streams(nullptr), - _mission_result_sub(-1), + _mission_manager(nullptr), _mission_pub(-1), + _mission_result_sub(-1), _mode(MAVLINK_MODE_NORMAL), _total_counter(0), _verbose(false), @@ -245,7 +246,6 @@ Mavlink::Mavlink() : _param_component_id(0), _param_system_type(0), _param_use_hil_gps(0), - _mission_manager(nullptr), /* performance counters */ _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")), diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 0dda2337e..ca01344d4 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -69,9 +69,9 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : _action_timeout(MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT), _retry_timeout(MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT), _max_count(DM_KEY_WAYPOINTS_OFFBOARD_0_MAX), + _dataman_id(0), _count(0), _current_seq(0), - _dataman_id(0), _transfer_dataman_id(0), _transfer_count(0), _transfer_seq(0), diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index eb8dcc717..126877651 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -72,10 +72,7 @@ Mission::Mission(Navigator *navigator, const char *name) : _mission_result({0}), _mission_type(MISSION_TYPE_NONE), _inited(false), - _dist_1wp_ok(false), - _need_takeoff(true), - _takeoff(false) - + _dist_1wp_ok(false) { /* load initial params */ updateParams(); @@ -203,7 +200,7 @@ Mission::update_offboard_mission() /* Check mission feasibility, for now do not handle the return value, * however warnings are issued to the gcs via mavlink from inside the MissionFeasiblityChecker */ - dm_item_t dm_current = DM_KEY_WAYPOINTS_OFFBOARD(_transfer_dataman_id); + dm_item_t dm_current = DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id); missionFeasiblityChecker.checkMissionFeasible(_navigator->get_vstatus()->is_rotary_wing, dm_current, (size_t) _offboard_mission.count, _navigator->get_geofence(), @@ -252,13 +249,12 @@ Mission::check_dist_1wp() } /* check if first waypoint is not too far from home */ - bool mission_valid = false; if (_param_dist_1wp.get() > 0.0f) { if (_navigator->get_vstatus()->condition_home_position_valid) { struct mission_item_s mission_item; /* find first waypoint (with lat/lon) item in datamanager */ - for (int i = 0; i < _offboard_mission.count; i++) { + for (unsigned i = 0; i < _offboard_mission.count; i++) { if (dm_read(DM_KEY_WAYPOINTS_OFFBOARD(_offboard_mission.dataman_id), i, &mission_item, sizeof(mission_item_s)) == sizeof(mission_item_s)) { @@ -281,7 +277,7 @@ Mission::check_dist_1wp() } else { /* item is too far from home */ - mavlink_log_info(_navigator->get_mavlink_fd(), "first wp is too far from home: %.1fm > %.1fm", dist_to_1wp, _param_dist_1wp.get()); + mavlink_log_info(_navigator->get_mavlink_fd(), "first wp is too far from home: %.1fm > %.1fm", (double)dist_to_1wp, (double)_param_dist_1wp.get()); return false; } } -- cgit v1.2.3 From 687612dd654bcdfb390bfdddf8a004b10119c2ac Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 10 Jul 2014 18:34:33 +0200 Subject: Do not abort if the sensor reset failed, only abort on no data --- src/modules/commander/airspeed_calibration.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 5d21d89d0..923c1a3ff 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -95,10 +95,8 @@ int do_airspeed_calibration(int mavlink_fd) } if (!paramreset_successful) { - warn("FAILED to set scale / offsets for airspeed"); - mavlink_log_critical(mavlink_fd, "dpress reset failed"); - mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name); - return ERROR; + warn("FAILED to reset - assuming analog"); + mavlink_log_critical(mavlink_fd, "assuming analog sensor"); } while (calibration_counter < calibration_count) { -- cgit v1.2.3 From dca8daeec54624001f02acb7ad6f4c2d7304a5fb Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 10 Jul 2014 21:37:00 +0200 Subject: mavlink: use all outputs in HIL mode --- src/modules/mavlink/mavlink_messages.cpp | 55 +++++++++++++------------------- 1 file changed, 23 insertions(+), 32 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 667be87b7..c7ad605c5 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1051,10 +1051,16 @@ protected: uint32_t mavlink_custom_mode; get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode); + float out[8]; + + const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2; + + /* scale outputs depending on system type */ if (mavlink_system.type == MAV_TYPE_QUADROTOR || mavlink_system.type == MAV_TYPE_HEXAROTOR || mavlink_system.type == MAV_TYPE_OCTOROTOR) { - /* set number of valid outputs depending on vehicle type */ + /* multirotors: set number of rotor outputs depending on type */ + unsigned n; switch (mavlink_system.type) { @@ -1071,59 +1077,44 @@ protected: break; } - /* scale / assign outputs depending on system type */ - float out[8]; - for (unsigned i = 0; i < 8; i++) { - if (i < n) { - if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) { - /* scale fake PWM out 900..2100 us to 0..1 for normal multirotors */ + if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) { + if (i < n) { + /* scale PWM out 900..2100 us to 0..1 for rotors */ out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); } else { - /* send 0 when disarmed */ - out[i] = 0.0f; + /* scale PWM out 900..2100 us to -1..1 for other channels */ + out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); } } else { - out[i] = -1.0f; + /* send 0 when disarmed */ + out[i] = 0.0f; } } - mavlink_msg_hil_controls_send(_channel, - hrt_absolute_time(), - out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7], - mavlink_base_mode, - 0); } else { - - /* fixed wing: scale all channels except throttle -1 .. 1 - * because we know that we set the mixers up this way - */ - - float out[8]; - - const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2; + /* fixed wing: scale throttle to 0..1 and other channels to -1..1 */ for (unsigned i = 0; i < 8; i++) { if (i != 3) { - /* scale fake PWM out 900..2100 us to -1..+1 for normal channels */ + /* scale PWM out 900..2100 us to -1..1 for normal channels */ out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); } else { - - /* scale fake PWM out 900..2100 us to 0..1 for throttle */ + /* scale PWM out 900..2100 us to 0..1 for throttle */ out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); } } - - mavlink_msg_hil_controls_send(_channel, - hrt_absolute_time(), - out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7], - mavlink_base_mode, - 0); } + + mavlink_msg_hil_controls_send(_channel, + hrt_absolute_time(), + out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7], + mavlink_base_mode, + 0); } } }; -- cgit v1.2.3 From c97e08bcf05455e9e9b582fe3216250a988890fb Mon Sep 17 00:00:00 2001 From: hxxnrx Date: Thu, 10 Jul 2014 21:50:23 +0200 Subject: Set IO PX4_I2C_BUS_ONBOARD I2C speed to 400KHz --- src/drivers/px4io/px4io_i2c.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) mode change 100644 => 100755 src/drivers/px4io/px4io_i2c.cpp diff --git a/src/drivers/px4io/px4io_i2c.cpp b/src/drivers/px4io/px4io_i2c.cpp old mode 100644 new mode 100755 index 19776c40a..c57ddf65b --- a/src/drivers/px4io/px4io_i2c.cpp +++ b/src/drivers/px4io/px4io_i2c.cpp @@ -79,7 +79,7 @@ device::Device } PX4IO_I2C::PX4IO_I2C(int bus, uint8_t address) : - I2C("PX4IO_i2c", nullptr, bus, address, 320000) + I2C("PX4IO_i2c", nullptr, bus, address, 400000) { _retries = 3; } -- cgit v1.2.3 From e8c5b8230d6dbdfdfb5ac9749a1b713d10c4521e Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Thu, 10 Jul 2014 23:01:41 -0400 Subject: px4io_uploader cleanup and minor optimization Remove redundant code Cleanup error handling in program function --- src/drivers/px4io/px4io_uploader.cpp | 51 ++++++++++++++---------------------- src/drivers/px4io/uploader.h | 1 - 2 files changed, 20 insertions(+), 32 deletions(-) diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp index d134c0246..bf6893a7e 100644 --- a/src/drivers/px4io/px4io_uploader.cpp +++ b/src/drivers/px4io/px4io_uploader.cpp @@ -204,12 +204,8 @@ PX4IO_Uploader::upload(const char *filenames[]) if (bl_rev <= 2) { ret = verify_rev2(fw_size); - } else if(bl_rev == 3) { - ret = verify_rev3(fw_size); } else { - /* verify rev 4 and higher still uses the same approach and - * every version *needs* to be verified. - */ + /* verify rev 3 and higher. Every version *needs* to be verified. */ ret = verify_rev3(fw_size); } @@ -276,14 +272,14 @@ PX4IO_Uploader::recv(uint8_t &c, unsigned timeout) int PX4IO_Uploader::recv(uint8_t *p, unsigned count) { + int ret; while (count--) { - int ret = recv(*p++, 5000); + ret = recv(*p++, 5000); if (ret != OK) - return ret; + break; } - - return OK; + return ret; } void @@ -314,21 +310,19 @@ PX4IO_Uploader::send(uint8_t c) #endif if (write(_io_fd, &c, 1) != 1) return -errno; - return OK; } int PX4IO_Uploader::send(uint8_t *p, unsigned count) { + int ret; while (count--) { - int ret = send(*p++); - + ret = send(*p++); if (ret != OK) - return ret; + break; } - - return OK; + return ret; } int @@ -419,12 +413,15 @@ PX4IO_Uploader::program(size_t fw_size) int ret; size_t sent = 0; - file_buf = (uint8_t *)malloc(PROG_MULTI_MAX); + file_buf = new uint8_t[PROG_MULTI_MAX]; if (!file_buf) { log("Can't allocate program buffer"); return -ENOMEM; } + ASSERT((fw_size & 3) == 0); + ASSERT((PROG_MULTI_MAX & 3) == 0); + log("programming %u bytes...", (unsigned)fw_size); ret = lseek(_fw_fd, 0, SEEK_SET); @@ -443,34 +440,26 @@ PX4IO_Uploader::program(size_t fw_size) (unsigned)sent, (int)count, (int)errno); - } - - if (count == 0) { - free(file_buf); - return OK; + ret = -errno; + break; } sent += count; - if (count < 0) - return -errno; - - ASSERT((count % 4) == 0); - send(PROTO_PROG_MULTI); send(count); - send(&file_buf[0], count); + send(file_buf, count); send(PROTO_EOC); ret = get_sync(1000); if (ret != OK) { - free(file_buf); - return ret; + break; } } - free(file_buf); - return OK; + + delete [] file_buf; + return ret; } int diff --git a/src/drivers/px4io/uploader.h b/src/drivers/px4io/uploader.h index 55f63eef9..3e2142cf2 100644 --- a/src/drivers/px4io/uploader.h +++ b/src/drivers/px4io/uploader.h @@ -75,7 +75,6 @@ private: INFO_FLASH_SIZE = 4, /**< max firmware size in bytes */ PROG_MULTI_MAX = 60, /**< protocol max is 255, must be multiple of 4 */ - READ_MULTI_MAX = 60, /**< protocol max is 255, something overflows with >= 64 */ }; -- cgit v1.2.3 From 50414257a8802fe7c51a370f598899c8b554914c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 09:09:57 +0200 Subject: Remove voltage field for digital sensors --- src/drivers/ets_airspeed/ets_airspeed.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index 1a7e068fe..d1a9fa57c 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -186,7 +186,6 @@ ETSAirspeed::collect() report.differential_pressure_filtered_pa = (float)diff_pres_pa; report.differential_pressure_raw_pa = (float)diff_pres_pa_raw; report.temperature = -1000.0f; - report.voltage = 0; report.max_differential_pressure_pa = _max_differential_pressure_pa; if (_airspeed_pub > 0 && !(_pub_blocked)) { -- cgit v1.2.3 From 56e1fe382b77200b3826b1ba438fc49ebab8f8ee Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 09:10:15 +0200 Subject: Remove voltage field for MEAS sensor --- src/drivers/meas_airspeed/meas_airspeed.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index c0f3c28e0..7763f1057 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -265,7 +265,6 @@ MEASAirspeed::collect() } report.differential_pressure_raw_pa = diff_press_pa_raw; - report.voltage = 0; report.max_differential_pressure_pa = _max_differential_pressure_pa; if (_airspeed_pub > 0 && !(_pub_blocked)) { -- cgit v1.2.3 From 3461d3d215843681b1537256d26b053e3f2b78e1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 09:10:35 +0200 Subject: Introduce analog scaling parameter for analog airspeed sensor --- src/modules/sensors/sensor_params.c | 10 ++++++++-- src/modules/sensors/sensors.cpp | 18 +++++++++--------- 2 files changed, 17 insertions(+), 11 deletions(-) diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 5deb471d6..6b90a1239 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -194,16 +194,22 @@ PARAM_DEFINE_FLOAT(SENS_ACC_ZSCALE, 1.0f); /** * Differential pressure sensor offset * + * The offset (zero-reading) in Pascal + * * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f); /** - * Differential pressure sensor analog enabled + * Differential pressure sensor analog scaling + * + * Pick the appropriate scaling from the datasheet. + * this number defines the (linear) conversion from voltage + * to Pascal (pa). * * @group Sensor Calibration */ -PARAM_DEFINE_INT32(SENS_DPRES_ANA, 0); +PARAM_DEFINE_FLOAT(SENS_DPRES_ANSC, 0); /** diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 6e2d906e6..0cad0c0e5 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -248,7 +248,7 @@ private: float accel_offset[3]; float accel_scale[3]; float diff_pres_offset_pa; - float diff_pres_analog_enabled; + float diff_pres_analog_scale; int board_rotation; int external_mag_rotation; @@ -311,7 +311,7 @@ private: param_t mag_offset[3]; param_t mag_scale[3]; param_t diff_pres_offset_pa; - param_t diff_pres_analog_enabled; + param_t diff_pres_analog_scale; param_t rc_map_roll; param_t rc_map_pitch; @@ -590,7 +590,7 @@ Sensors::Sensors() : /* Differential pressure offset */ _parameter_handles.diff_pres_offset_pa = param_find("SENS_DPRES_OFF"); - _parameter_handles.diff_pres_analog_enabled = param_find("SENS_DPRES_ANA"); + _parameter_handles.diff_pres_analog_scale = param_find("SENS_DPRES_ANSC"); _parameter_handles.battery_voltage_scaling = param_find("BAT_V_SCALING"); _parameter_handles.battery_current_scaling = param_find("BAT_C_SCALING"); @@ -798,7 +798,7 @@ Sensors::parameters_update() /* Airspeed offset */ param_get(_parameter_handles.diff_pres_offset_pa, &(_parameters.diff_pres_offset_pa)); - param_get(_parameter_handles.diff_pres_analog_enabled, &(_parameters.diff_pres_analog_enabled)); + param_get(_parameter_handles.diff_pres_analog_scale, &(_parameters.diff_pres_analog_scale)); /* scaling of ADC ticks to battery voltage */ if (param_get(_parameter_handles.battery_voltage_scaling, &(_parameters.battery_voltage_scaling)) != OK) { @@ -1323,22 +1323,22 @@ Sensors::adc_poll(struct sensor_combined_s &raw) } else if (ADC_AIRSPEED_VOLTAGE_CHANNEL == buf_adc[i].am_channel) { /* calculate airspeed, raw is the difference from */ - float voltage = (float)(buf_adc[i].am_data) * 3.3f / 4096.0f * 2.0f; //V_ref/4096 * (voltage divider factor) + float voltage = (float)(buf_adc[i].am_data) * 3.3f / 4096.0f * 2.0f; // V_ref/4096 * (voltage divider factor) /** * The voltage divider pulls the signal down, only act on * a valid voltage from a connected sensor. Also assume a non- * zero offset from the sensor if its connected. */ - if (voltage > 0.4f && (_parameters.diff_pres_analog_enabled > 0)) { + if (voltage > 0.4f && (_parameters.diff_pres_analog_scale > 0)) { - float diff_pres_pa = voltage * 1000.0f - _parameters.diff_pres_offset_pa; //for MPXV7002DP sensor + float diff_pres_pa = voltage * _parameters.diff_pres_analog_scale; _diff_pres.timestamp = t; - _diff_pres.differential_pressure_pa = diff_pres_pa; + _diff_pres.differential_pressure_pa = diff_pres_pa - _parameters.diff_pres_offset_pa; + _diff_pres.differential_pressure_raw_pa = diff_pres_pa; _diff_pres.differential_pressure_filtered_pa = diff_pres_pa; _diff_pres.temperature = -1000.0f; - _diff_pres.voltage = voltage; /* announce the airspeed if needed, just publish else */ if (_diff_pres_pub > 0) { -- cgit v1.2.3 From 8d081a8b0dd002cda075ee9d8e087fdf54722ccf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 09:11:03 +0200 Subject: uORB: Remove voltage field from airspeed --- src/modules/uORB/topics/differential_pressure.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/uORB/topics/differential_pressure.h b/src/modules/uORB/topics/differential_pressure.h index 01e14cda9..cd48d3cb2 100644 --- a/src/modules/uORB/topics/differential_pressure.h +++ b/src/modules/uORB/topics/differential_pressure.h @@ -58,7 +58,6 @@ struct differential_pressure_s { float differential_pressure_raw_pa; /**< Raw differential pressure reading (may be negative) */ float differential_pressure_filtered_pa; /**< Low pass filtered differential pressure reading */ float max_differential_pressure_pa; /**< Maximum differential pressure reading */ - float voltage; /**< Voltage from analog airspeed sensors (voltage divider already compensated) */ float temperature; /**< Temperature provided by sensor, -1000.0f if unknown */ }; -- cgit v1.2.3 From 25f3f6e7f2dd87a831d25a9348a67ed918407d96 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 09:12:31 +0200 Subject: airspeed calibration improvements for analog sensors --- src/modules/commander/airspeed_calibration.cpp | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 923c1a3ff..12e527a68 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -76,7 +76,7 @@ int do_airspeed_calibration(int mavlink_fd) /* Reset sensor parameters */ struct airspeed_scale airscale = { - 0.0f, + diff_pres_offset, 1.0f, }; @@ -97,6 +97,12 @@ int do_airspeed_calibration(int mavlink_fd) if (!paramreset_successful) { warn("FAILED to reset - assuming analog"); mavlink_log_critical(mavlink_fd, "assuming analog sensor"); + + if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) { + mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG); + close(diff_pres_sub); + return ERROR; + } } while (calibration_counter < calibration_count) { -- cgit v1.2.3 From 4c13c67504fb2b66c97ac6b902e67a864f1173e8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 14:02:22 +0200 Subject: Hotfix: Close fd before reusing it again --- src/modules/commander/state_machine_helper.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 6b96e3a3f..ca95f139e 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -666,6 +666,8 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) } if (!status->is_rotary_wing) { + /* accel done, close it */ + close(fd); fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); if (fd < 0) { -- cgit v1.2.3 From 7ea76336ca03f724ba76661f986cc12cd0466ff8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 14:24:07 +0200 Subject: Better Doxygen for topics, no code changes --- src/drivers/drv_px4flow.h | 16 ++++++++++++++-- src/drivers/drv_range_finder.h | 9 +++++++++ src/drivers/drv_rc_input.h | 9 +++++++++ 3 files changed, 32 insertions(+), 2 deletions(-) diff --git a/src/drivers/drv_px4flow.h b/src/drivers/drv_px4flow.h index bef02d54e..76ec55c3e 100644 --- a/src/drivers/drv_px4flow.h +++ b/src/drivers/drv_px4flow.h @@ -46,10 +46,18 @@ #define PX4FLOW_DEVICE_PATH "/dev/px4flow" +/** + * @addtogroup topics + * @{ + */ + /** * Optical flow in NED body frame in SI units. * * @see http://en.wikipedia.org/wiki/International_System_of_Units + * + * @warning If possible the usage of the raw flow and performing rotation-compensation + * using the autopilot angular rate estimate is recommended. */ struct px4flow_report { @@ -57,14 +65,18 @@ struct px4flow_report { int16_t flow_raw_x; /**< flow in pixels in X direction, not rotation-compensated */ int16_t flow_raw_y; /**< flow in pixels in Y direction, not rotation-compensated */ - float flow_comp_x_m; /**< speed over ground in meters, rotation-compensated */ - float flow_comp_y_m; /**< speed over ground in meters, rotation-compensated */ + float flow_comp_x_m; /**< speed over ground in meters per second, rotation-compensated */ + float flow_comp_y_m; /**< speed over ground in meters per second, rotation-compensated */ float ground_distance_m; /**< Altitude / distance to ground in meters */ uint8_t quality; /**< Quality of the measurement, 0: bad quality, 255: maximum quality */ uint8_t sensor_id; /**< id of the sensor emitting the flow value */ }; +/** + * @} + */ + /* * ObjDev tag for px4flow data. */ diff --git a/src/drivers/drv_range_finder.h b/src/drivers/drv_range_finder.h index e45939b37..0f8362f58 100644 --- a/src/drivers/drv_range_finder.h +++ b/src/drivers/drv_range_finder.h @@ -50,6 +50,11 @@ enum RANGE_FINDER_TYPE { RANGE_FINDER_TYPE_LASER = 0, }; +/** + * @addtogroup topics + * @{ + */ + /** * range finder report structure. Reads from the device must be in multiples of this * structure. @@ -64,6 +69,10 @@ struct range_finder_report { uint8_t valid; /**< 1 == within sensor range, 0 = outside sensor range */ }; +/** + * @} + */ + /* * ObjDev tag for raw range finder data. */ diff --git a/src/drivers/drv_rc_input.h b/src/drivers/drv_rc_input.h index 20763e265..47fa8fa59 100644 --- a/src/drivers/drv_rc_input.h +++ b/src/drivers/drv_rc_input.h @@ -67,6 +67,11 @@ */ #define RC_INPUT_RSSI_MAX 255 +/** + * @addtogroup topics + * @{ + */ + /** * Input signal type, value is a control position from zero to 100 * percent. @@ -141,6 +146,10 @@ struct rc_input_values { rc_input_t values[RC_INPUT_MAX_CHANNELS]; }; +/** + * @} + */ + /* * ObjDev tag for R/C inputs. */ -- cgit v1.2.3 From ee573fea9d27e7925b375abd95d540c0fda30d4c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 14:25:16 +0200 Subject: GPS driver: Print velocity as part of status command --- src/drivers/gps/gps.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index 401b65dd4..34dd63086 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -127,7 +127,7 @@ private: /** * Try to configure the GPS, handle outgoing communication to the GPS */ - void config(); + void config(); /** * Trampoline to the worker task @@ -486,6 +486,8 @@ GPS::print_info() warnx("position lock: %dD, satellites: %d, last update: %8.4fms ago", (int)_report_gps_pos.fix_type, _report_gps_pos.satellites_used, (double)(hrt_absolute_time() - _report_gps_pos.timestamp_position) / 1000.0); warnx("lat: %d, lon: %d, alt: %d", _report_gps_pos.lat, _report_gps_pos.lon, _report_gps_pos.alt); + warnx("vel: %.2fm/s, %.2fm/s, %.2fm/s", (double)_report_gps_pos.vel_n_m_s, + (double)_report_gps_pos.vel_e_m_s, (double)_report_gps_pos.vel_d_m_s); warnx("eph: %.2fm, epv: %.2fm", (double)_report_gps_pos.eph, (double)_report_gps_pos.epv); warnx("rate position: \t%6.2f Hz", (double)_Helper->get_position_update_rate()); warnx("rate velocity: \t%6.2f Hz", (double)_Helper->get_velocity_update_rate()); -- cgit v1.2.3 From b97c867420f477f2c3a7dbc073975f5d872194cb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 14:51:13 +0200 Subject: Add a check command and fix error reporting --- src/modules/commander/commander.cpp | 19 ++++++++++++------- src/modules/commander/state_machine_helper.cpp | 23 ++++++++++------------- src/modules/commander/state_machine_helper.h | 2 ++ 3 files changed, 24 insertions(+), 20 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 2058cd92e..106f05f57 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -286,15 +286,20 @@ int commander_main(int argc, char *argv[]) exit(0); } - if (!strcmp(argv[1], "status")) { - if (thread_running) { - warnx("\tcommander is running"); - print_status(); + /* commands needing the app to run below */ + if (!thread_running) { + warnx("\tcommander not started"); + exit(1); + } - } else { - warnx("\tcommander not started"); - } + if (!strcmp(argv[1], "status")) { + print_status(); + exit(0); + } + if (!strcmp(argv[1], "check")) { + int checkres = prearm_check(&status, mavlink_fd); + warnx("FINAL RESULT: %s", (checkres == 0) ? "OK" : "FAILED"); exit(0); } diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index ca95f139e..d6b4d43ad 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -70,8 +70,6 @@ #endif static const int ERROR = -1; -static int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd); - // This array defines the arming state transitions. The rows are the new state, and the columns // are the current state. Using new state and current state you can index into the array which // will be true for a valid transition or false for a invalid transition. In some cases even @@ -622,12 +620,13 @@ bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_en int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) { int ret; + bool failed = false; int fd = open(ACCEL_DEVICE_PATH, O_RDONLY); if (fd < 0) { mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL SENSOR MISSING"); - ret = fd; + failed = true; goto system_eval; } @@ -635,6 +634,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) if (ret != OK) { mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL CALIBRATION"); + failed = true; goto system_eval; } @@ -646,22 +646,20 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) /* evaluate values */ float accel_scale = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z); - if (accel_scale < 9.78f || accel_scale > 9.83f) { + if (accel_scale < 9.75f || accel_scale > 9.85f) { mavlink_log_info(mavlink_fd, "#audio: Accelerometer calibration recommended."); } if (accel_scale > 30.0f /* m/s^2 */) { mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL RANGE"); /* this is frickin' fatal */ - ret = ERROR; + failed = true; goto system_eval; - } else { - ret = OK; } } else { mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL READ"); /* this is frickin' fatal */ - ret = ERROR; + failed = true; goto system_eval; } @@ -672,7 +670,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) if (fd < 0) { mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED SENSOR MISSING"); - ret = fd; + failed = true; goto system_eval; } @@ -681,20 +679,19 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) ret = read(fd, &diff_pres, sizeof(diff_pres)); if (ret == sizeof(diff_pres)) { - if (fabsf(diff_pres.differential_pressure_filtered_pa > 5.0f)) { + if (fabsf(diff_pres.differential_pressure_filtered_pa > 6.0f)) { mavlink_log_critical(mavlink_fd, "#audio: WARNING AIRSPEED CALIBRATION MISSING"); // XXX do not make this fatal yet - ret = OK; } } else { mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED READ"); /* this is frickin' fatal */ - ret = ERROR; + failed = true; goto system_eval; } } system_eval: close(fd); - return ret; + return (!failed); } diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h index 11072403e..ddc5bf154 100644 --- a/src/modules/commander/state_machine_helper.h +++ b/src/modules/commander/state_machine_helper.h @@ -67,4 +67,6 @@ transition_result_t hil_state_transition(hil_state_t new_state, int status_pub, bool set_nav_state(struct vehicle_status_s *status, const bool data_link_loss_enabled, const bool mission_finished); +int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd); + #endif /* STATE_MACHINE_HELPER_H_ */ -- cgit v1.2.3 From a82d4fbb115e949a6a5c12d46308df1c20abfd99 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 14:55:46 +0200 Subject: Hotfix: fix typo --- src/modules/commander/commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 106f05f57..6138a4c37 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -308,7 +308,7 @@ int commander_main(int argc, char *argv[]) exit(0); } - if (!strcmp(argv[1], "2")) { + if (!strcmp(argv[1], "disarm")) { arm_disarm(false, mavlink_fd, "command line"); exit(0); } -- cgit v1.2.3 From 79c5d434bd5911d11e6968e0a339b40a6f82e033 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 15:10:11 +0200 Subject: Commander: More hotfixes to prearm check routine --- src/modules/commander/commander.cpp | 5 ++++- src/modules/commander/state_machine_helper.cpp | 5 +++-- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 6138a4c37..18761665a 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -298,7 +298,9 @@ int commander_main(int argc, char *argv[]) } if (!strcmp(argv[1], "check")) { - int checkres = prearm_check(&status, mavlink_fd); + int mavlink_fd_local = open(MAVLINK_LOG_DEVICE, 0); + int checkres = prearm_check(&status, mavlink_fd_local); + close(mavlink_fd_local); warnx("FINAL RESULT: %s", (checkres == 0) ? "OK" : "FAILED"); exit(0); } @@ -329,6 +331,7 @@ void usage(const char *reason) void print_status() { + warnx("type: %s", (status.is_rotary_wing) ? "ROTARY" : "PLANE"); warnx("usb powered: %s", (on_usb_power) ? "yes" : "no"); /* read all relevant states */ diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index d6b4d43ad..5cbc95920 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -664,11 +664,12 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) } if (!status->is_rotary_wing) { + /* accel done, close it */ close(fd); fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); - if (fd < 0) { + if (fd <= 0) { mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED SENSOR MISSING"); failed = true; goto system_eval; @@ -693,5 +694,5 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) system_eval: close(fd); - return (!failed); + return (failed); } -- cgit v1.2.3 From a118e8dbdd72e23a47841577dfcd7a45007eaedc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 15:17:21 +0200 Subject: Make commander error message more verbose --- src/modules/commander/state_machine_helper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 5cbc95920..ce1bd9ada 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -647,7 +647,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) float accel_scale = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z); if (accel_scale < 9.75f || accel_scale > 9.85f) { - mavlink_log_info(mavlink_fd, "#audio: Accelerometer calibration recommended."); + mavlink_log_info(mavlink_fd, "#audio: Accel calib. recommended (%8.4f).", (double)accel_scale); } if (accel_scale > 30.0f /* m/s^2 */) { -- cgit v1.2.3 From 11d9724563f005ed722d326e8bef125bfec29865 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 16:03:27 +0200 Subject: Stop warning users just because they shake a bit, be more strict to catch sensor failures or calibration errors in time --- src/modules/commander/state_machine_helper.cpp | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index ce1bd9ada..363f5e8eb 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -644,14 +644,11 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) if (ret == sizeof(acc)) { /* evaluate values */ - float accel_scale = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z); + float accel_magnitude = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z); - if (accel_scale < 9.75f || accel_scale > 9.85f) { - mavlink_log_info(mavlink_fd, "#audio: Accel calib. recommended (%8.4f).", (double)accel_scale); - } - - if (accel_scale > 30.0f /* m/s^2 */) { + if (accel_magnitude < 4.0f || accel_magnitude > 15.0f /* m/s^2 */) { mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL RANGE"); + mavlink_log_info(mavlink_fd, "#audio: hold still while arming"); /* this is frickin' fatal */ failed = true; goto system_eval; -- cgit v1.2.3 From aa055825984c121c0d2b74d81463282f6400688d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 21:04:09 +0200 Subject: FMUv1: Reduce excessive stack sizes --- nuttx-configs/px4fmu-v1/nsh/defconfig | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index f2c7d22bf..6717ae19a 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -417,8 +417,8 @@ CONFIG_PREALLOC_TIMERS=50 # # Stack and heap information # -CONFIG_IDLETHREAD_STACKSIZE=4096 -CONFIG_USERMAIN_STACKSIZE=3500 +CONFIG_IDLETHREAD_STACKSIZE=3500 +CONFIG_USERMAIN_STACKSIZE=3000 CONFIG_PTHREAD_STACK_MIN=512 CONFIG_PTHREAD_STACK_DEFAULT=2048 -- cgit v1.2.3 From c474d2cbf1a9c78be5804b224c504b57f9248760 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 21:04:34 +0200 Subject: FMUv2: Reduce excessive stack sizes --- nuttx-configs/px4fmu-v2/nsh/defconfig | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/nuttx-configs/px4fmu-v2/nsh/defconfig b/nuttx-configs/px4fmu-v2/nsh/defconfig index 7d5e6e9df..a55c95a29 100644 --- a/nuttx-configs/px4fmu-v2/nsh/defconfig +++ b/nuttx-configs/px4fmu-v2/nsh/defconfig @@ -451,8 +451,8 @@ CONFIG_PREALLOC_TIMERS=50 # # Stack and heap information # -CONFIG_IDLETHREAD_STACKSIZE=6000 -CONFIG_USERMAIN_STACKSIZE=4096 +CONFIG_IDLETHREAD_STACKSIZE=3500 +CONFIG_USERMAIN_STACKSIZE=3000 CONFIG_PTHREAD_STACK_MIN=512 CONFIG_PTHREAD_STACK_DEFAULT=2048 -- cgit v1.2.3 From a3210f31fe431b31b971f9d25d41a5c18734120c Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 11 Jul 2014 21:30:59 +0200 Subject: Create a mixer for the Wing Wing. --- ROMFS/px4fmu_common/init.d/3033_wingwing | 2 +- ROMFS/px4fmu_common/mixers/FMU_wingwing | 70 ++++++++++++++++++++++++++++++++ 2 files changed, 71 insertions(+), 1 deletion(-) create mode 100644 ROMFS/px4fmu_common/mixers/FMU_wingwing diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing index fff4b58df..75163168e 100644 --- a/ROMFS/px4fmu_common/init.d/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/3033_wingwing @@ -32,7 +32,7 @@ then param set FW_THR_CRUISE 0.65 fi -set MIXER FMU_Q +set MIXER FMU_wingwing # Provide ESC a constant 1000 us pulse set PWM_OUTPUTS 4 set PWM_DISARMED 1000 diff --git a/ROMFS/px4fmu_common/mixers/FMU_wingwing b/ROMFS/px4fmu_common/mixers/FMU_wingwing new file mode 100644 index 000000000..806bfec73 --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/FMU_wingwing @@ -0,0 +1,70 @@ +Delta-wing mixer for PX4FMU +=========================== + +Designed for Wing Wing Z-84 + +This file defines mixers suitable for controlling a delta wing aircraft using +PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU +servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is +assumed to be unused. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch) and 3 (thrust). + +See the README for more information on the scaler format. + +Elevon mixers +------------- +Three scalers total (output, roll, pitch). + +On the assumption that the two elevon servos are physically reversed, the pitch +input is inverted between the two servos. + +The scaling factor for roll inputs is adjusted to implement differential travel +for the elevons. + +M: 2 +O: 10000 10000 0 -10000 10000 +S: 0 0 -6000 -6000 0 -10000 10000 +S: 0 1 6500 6500 0 -10000 10000 + +M: 2 +O: 10000 10000 0 -10000 10000 +S: 0 0 -6000 -6000 0 -10000 10000 +S: 0 1 -6500 -6500 0 -10000 10000 + +Output 2 +-------- +This mixer is empty. + +Z: + +Motor speed mixer +----------------- +Two scalers total (output, thrust). + +This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1) +range. Inputs below zero are treated as zero. + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + +Gimbal / flaps / payload mixer for last four channels +----------------------------------------------------- + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 4 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 5 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 6 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 7 10000 10000 0 -10000 10000 -- cgit v1.2.3 From e4264aad825540c159888b68fc2a0dec599b2e9b Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 11 Jul 2014 21:34:51 +0200 Subject: The wing wing is too small to have flaps, gimbals, etc. --- ROMFS/px4fmu_common/mixers/FMU_wingwing | 19 ------------------- 1 file changed, 19 deletions(-) diff --git a/ROMFS/px4fmu_common/mixers/FMU_wingwing b/ROMFS/px4fmu_common/mixers/FMU_wingwing index 806bfec73..08333ba5c 100644 --- a/ROMFS/px4fmu_common/mixers/FMU_wingwing +++ b/ROMFS/px4fmu_common/mixers/FMU_wingwing @@ -49,22 +49,3 @@ range. Inputs below zero are treated as zero. M: 1 O: 10000 10000 0 -10000 10000 S: 0 3 0 20000 -10000 -10000 10000 - -Gimbal / flaps / payload mixer for last four channels ------------------------------------------------------ - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 4 10000 10000 0 -10000 10000 - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 5 10000 10000 0 -10000 10000 - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 6 10000 10000 0 -10000 10000 - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 7 10000 10000 0 -10000 10000 -- cgit v1.2.3 From 0a3a13ac7061566aac97321f09329b6228f0ed7e Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 11 Jul 2014 21:38:12 +0200 Subject: Updated following flight tests today. --- ROMFS/px4fmu_common/init.d/3033_wingwing | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing index 765685ccc..92f592aaf 100644 --- a/ROMFS/px4fmu_common/init.d/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/3033_wingwing @@ -30,14 +30,13 @@ then param set FW_RR_I 0.005 param set FW_RR_IMAX 0.2 param set FW_RR_P 0.04 - param set FW_THR_CRUISE 0.65 param set MT_TKF_PIT_MAX 30.0 param set MT_ACC_D 0.2 param set MT_ACC_P 0.6 param set MT_A_LP 0.5 param set MT_PIT_OFF 0.1 param set MT_PIT_I 0.1 - param set MT_THR_OFF 0.12 + param set MT_THR_OFF 0.65 param set MT_THR_I 0.35 param set MT_THR_P 0.2 param set MT_THR_FF 1.5 -- cgit v1.2.3 From f8115e4e2e2cc0ad55949016c7872125a6727fac Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Fri, 11 Jul 2014 21:51:35 +0200 Subject: Renamed mixer file. --- ROMFS/px4fmu_common/init.d/3033_wingwing | 2 +- ROMFS/px4fmu_common/mixers/FMU_wingwing | 51 -------------------------------- ROMFS/px4fmu_common/mixers/wingwing.mix | 51 ++++++++++++++++++++++++++++++++ 3 files changed, 52 insertions(+), 52 deletions(-) delete mode 100644 ROMFS/px4fmu_common/mixers/FMU_wingwing create mode 100644 ROMFS/px4fmu_common/mixers/wingwing.mix diff --git a/ROMFS/px4fmu_common/init.d/3033_wingwing b/ROMFS/px4fmu_common/init.d/3033_wingwing index 75163168e..3cbbd555e 100644 --- a/ROMFS/px4fmu_common/init.d/3033_wingwing +++ b/ROMFS/px4fmu_common/init.d/3033_wingwing @@ -32,7 +32,7 @@ then param set FW_THR_CRUISE 0.65 fi -set MIXER FMU_wingwing +set MIXER wingwing # Provide ESC a constant 1000 us pulse set PWM_OUTPUTS 4 set PWM_DISARMED 1000 diff --git a/ROMFS/px4fmu_common/mixers/FMU_wingwing b/ROMFS/px4fmu_common/mixers/FMU_wingwing deleted file mode 100644 index 08333ba5c..000000000 --- a/ROMFS/px4fmu_common/mixers/FMU_wingwing +++ /dev/null @@ -1,51 +0,0 @@ -Delta-wing mixer for PX4FMU -=========================== - -Designed for Wing Wing Z-84 - -This file defines mixers suitable for controlling a delta wing aircraft using -PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU -servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is -assumed to be unused. - -Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 -(roll), 1 (pitch) and 3 (thrust). - -See the README for more information on the scaler format. - -Elevon mixers -------------- -Three scalers total (output, roll, pitch). - -On the assumption that the two elevon servos are physically reversed, the pitch -input is inverted between the two servos. - -The scaling factor for roll inputs is adjusted to implement differential travel -for the elevons. - -M: 2 -O: 10000 10000 0 -10000 10000 -S: 0 0 -6000 -6000 0 -10000 10000 -S: 0 1 6500 6500 0 -10000 10000 - -M: 2 -O: 10000 10000 0 -10000 10000 -S: 0 0 -6000 -6000 0 -10000 10000 -S: 0 1 -6500 -6500 0 -10000 10000 - -Output 2 --------- -This mixer is empty. - -Z: - -Motor speed mixer ------------------ -Two scalers total (output, thrust). - -This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1) -range. Inputs below zero are treated as zero. - -M: 1 -O: 10000 10000 0 -10000 10000 -S: 0 3 0 20000 -10000 -10000 10000 diff --git a/ROMFS/px4fmu_common/mixers/wingwing.mix b/ROMFS/px4fmu_common/mixers/wingwing.mix new file mode 100644 index 000000000..08333ba5c --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/wingwing.mix @@ -0,0 +1,51 @@ +Delta-wing mixer for PX4FMU +=========================== + +Designed for Wing Wing Z-84 + +This file defines mixers suitable for controlling a delta wing aircraft using +PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU +servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is +assumed to be unused. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch) and 3 (thrust). + +See the README for more information on the scaler format. + +Elevon mixers +------------- +Three scalers total (output, roll, pitch). + +On the assumption that the two elevon servos are physically reversed, the pitch +input is inverted between the two servos. + +The scaling factor for roll inputs is adjusted to implement differential travel +for the elevons. + +M: 2 +O: 10000 10000 0 -10000 10000 +S: 0 0 -6000 -6000 0 -10000 10000 +S: 0 1 6500 6500 0 -10000 10000 + +M: 2 +O: 10000 10000 0 -10000 10000 +S: 0 0 -6000 -6000 0 -10000 10000 +S: 0 1 -6500 -6500 0 -10000 10000 + +Output 2 +-------- +This mixer is empty. + +Z: + +Motor speed mixer +----------------- +Two scalers total (output, thrust). + +This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1) +range. Inputs below zero are treated as zero. + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 -- cgit v1.2.3 From 899657613e44f0d4bbdb66644b35420d7381ff99 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 22:09:25 +0200 Subject: airspeed cal: Improve user feedback --- src/modules/commander/airspeed_calibration.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 12e527a68..7599fc777 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -96,7 +96,7 @@ int do_airspeed_calibration(int mavlink_fd) if (!paramreset_successful) { warn("FAILED to reset - assuming analog"); - mavlink_log_critical(mavlink_fd, "assuming analog sensor"); + mavlink_log_critical(mavlink_fd, "If analog sens, retry with [SENS_DPRES_ANSC=1000]"); if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) { mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG); -- cgit v1.2.3 From e3afb669cae54b042f453605601fed861c52ee45 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 22:09:47 +0200 Subject: sensors: Fix usage of offset for measurements --- src/modules/sensors/sensor_params.c | 2 +- src/modules/sensors/sensors.cpp | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 6b90a1239..8f6e7abe6 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -205,7 +205,7 @@ PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f); * * Pick the appropriate scaling from the datasheet. * this number defines the (linear) conversion from voltage - * to Pascal (pa). + * to Pascal (pa). For the MPXV7002DP this is 1000. * * @group Sensor Calibration */ diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 0cad0c0e5..cda79693d 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -1330,12 +1330,12 @@ Sensors::adc_poll(struct sensor_combined_s &raw) * a valid voltage from a connected sensor. Also assume a non- * zero offset from the sensor if its connected. */ - if (voltage > 0.4f && (_parameters.diff_pres_analog_scale > 0)) { + if (voltage > 0.4f && (_parameters.diff_pres_analog_scale > 0.0f)) { - float diff_pres_pa = voltage * _parameters.diff_pres_analog_scale; + float diff_pres_pa = voltage * _parameters.diff_pres_analog_scale - _parameters.diff_pres_offset_pa; _diff_pres.timestamp = t; - _diff_pres.differential_pressure_pa = diff_pres_pa - _parameters.diff_pres_offset_pa; + _diff_pres.differential_pressure_pa = diff_pres_pa; _diff_pres.differential_pressure_raw_pa = diff_pres_pa; _diff_pres.differential_pressure_filtered_pa = diff_pres_pa; _diff_pres.temperature = -1000.0f; -- cgit v1.2.3 From 9c63aba9a72083afe1e5f818c6559760c5b6b1cc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 11 Jul 2014 22:44:54 +0200 Subject: Ensure NaN check is executed before any parts of the filter are run. Fix GPS velocity reset for case of initialized GPS --- .../ekf_att_pos_estimator_main.cpp | 26 +++++++++++++--------- 1 file changed, 15 insertions(+), 11 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index 5d768b73d..bc5f709e5 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -1140,6 +1140,20 @@ FixedwingEstimator::task_main() float initVelNED[3]; + // Guard before running any parts of the filter + // of NaN / invalid values + if (_ekf->statesInitialised) { + + // We're apparently initialized in this case now + + int check = check_filter_state(); + + if (check) { + // Let the system re-initialize itself + continue; + } + } + /* Initialize the filter first */ if (!_gps_initialized && _gps.fix_type > 2 && _gps.eph < _parameters.pos_stddev_threshold && _gps.epv < _parameters.pos_stddev_threshold) { @@ -1204,16 +1218,6 @@ FixedwingEstimator::task_main() _ekf->InitialiseFilter(initVelNED, 0.0, 0.0, 0.0f, 0.0f); } else if (_ekf->statesInitialised) { - // We're apparently initialized in this case now - - int check = check_filter_state(); - - if (check) { - // Let the system re-initialize itself - continue; - } - - // Run the strapdown INS equations every IMU update _ekf->UpdateStrapdownEquationsNED(); #if 0 @@ -1281,7 +1285,7 @@ FixedwingEstimator::task_main() // run the fusion step _ekf->FuseVelposNED(); - } else if (_ekf->statesInitialised) { + } else if (!_gps_initialized && _ekf->statesInitialised) { // Convert GPS measurements to Pos NE, hgt and Vel NED _ekf->velNED[0] = 0.0f; _ekf->velNED[1] = 0.0f; -- cgit v1.2.3 From 2fa4434a03abe057e65a5c8ba29f8cd9cd75ca93 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 00:17:50 +0200 Subject: Limit output of driver to positive range --- src/modules/sensors/sensors.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index cda79693d..1ffd7f02f 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -501,6 +501,7 @@ Sensors::Sensors() : _battery_current_timestamp(0) { memset(&_rc, 0, sizeof(_rc)); + memset(&_diff_pres, 0, sizeof(_diff_pres)); /* basic r/c parameters */ for (unsigned i = 0; i < _rc_max_chan_count; i++) { @@ -1332,12 +1333,13 @@ Sensors::adc_poll(struct sensor_combined_s &raw) */ if (voltage > 0.4f && (_parameters.diff_pres_analog_scale > 0.0f)) { - float diff_pres_pa = voltage * _parameters.diff_pres_analog_scale - _parameters.diff_pres_offset_pa; + float diff_pres_pa_raw = voltage * _parameters.diff_pres_analog_scale - _parameters.diff_pres_offset_pa; + float diff_pres_pa = (diff_pres_pa_raw > 0.0f) ? diff_pres_pa_raw : 0.0f; _diff_pres.timestamp = t; _diff_pres.differential_pressure_pa = diff_pres_pa; - _diff_pres.differential_pressure_raw_pa = diff_pres_pa; - _diff_pres.differential_pressure_filtered_pa = diff_pres_pa; + _diff_pres.differential_pressure_raw_pa = diff_pres_pa_raw; + _diff_pres.differential_pressure_filtered_pa = (_diff_pres.differential_pressure_filtered_pa * 0.9f) + (diff_pres_pa * 0.1f); _diff_pres.temperature = -1000.0f; /* announce the airspeed if needed, just publish else */ -- cgit v1.2.3 From 065bf013a407da5e2a70db82013126c20e2ad429 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 14:29:30 +0200 Subject: More obvious error message for mission reject --- src/modules/navigator/mission.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 126877651..ba766cd10 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -277,7 +277,7 @@ Mission::check_dist_1wp() } else { /* item is too far from home */ - mavlink_log_info(_navigator->get_mavlink_fd(), "first wp is too far from home: %.1fm > %.1fm", (double)dist_to_1wp, (double)_param_dist_1wp.get()); + mavlink_log_critical(_navigator->get_mavlink_fd(), "Waypoint too far: %d m,[MIS_DIST_1WP=%d]", (int)dist_to_1wp, (int)_param_dist_1wp.get()); return false; } } -- cgit v1.2.3 From 5616a07bf306b3fa2bc70078e9c8c26a086065dc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 14:29:56 +0200 Subject: Final default values and more comments for params --- src/modules/navigator/mission_params.c | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c index 5cb3782c9..881caa24e 100644 --- a/src/modules/navigator/mission_params.c +++ b/src/modules/navigator/mission_params.c @@ -59,22 +59,26 @@ PARAM_DEFINE_FLOAT(MIS_TAKEOFF_ALT, 10.0f); /** - * Enable onboard mission + * Enable persistent onboard mission storage + * + * When enabled, missions that have been uploaded by the GCS are stored + * and reloaded after reboot persistently. * * @min 0 * @max 1 * @group Mission */ -PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 0); +PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 1); /** * Maximal horizontal distance from home to first waypoint * - * Failsafe check to prevent running mission stored from previous flight on new place. - * Value < 0 means that check disabled. + * Failsafe check to prevent running mission stored from previous flight at a new takeoff location. + * Set a value of zero or less to disable. The mission will not be started if the current + * waypoint is more distant than MIS_DIS_1WP from the current position. * - * @min -1 - * @max 200 + * @min 0 + * @max 250 * @group Mission */ -PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 50); +PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 175); -- cgit v1.2.3 From 629ab5540fcb62b4c0ecc49e964f2d3fcc0b8a4d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 14:30:49 +0200 Subject: Fix severity handling of text messages --- src/modules/mavlink/mavlink_main.cpp | 39 ++++++++++++++++++++++++------ src/modules/mavlink/mavlink_main.h | 46 ++++++++++++++++++++++++++++-------- 2 files changed, 68 insertions(+), 17 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 0d685c3d8..cd0581af4 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -492,6 +492,7 @@ Mavlink::mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg) // printf("logmsg: %s\n", txt); struct mavlink_logmessage msg; strncpy(msg.text, txt, sizeof(msg.text)); + msg.severity = (unsigned char)cmd; Mavlink *inst; LL_FOREACH(_mavlink_instances, inst) { @@ -840,7 +841,7 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav (req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) { /* Start sending parameters */ mavlink_pm_start_queued_send(); - send_statustext("[mavlink pm] sending list"); + send_statustext_info("[pm] sending list"); } } break; @@ -864,7 +865,7 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav if (param == PARAM_INVALID) { char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; sprintf(buf, "[pm] unknown: %s", name); - send_statustext(buf); + send_statustext_info(buf); } else { /* set and send parameter */ @@ -901,17 +902,28 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav } int -Mavlink::send_statustext(const char *string) +Mavlink::send_statustext_info(const char *string) { - return send_statustext(MAV_SEVERITY_INFO, string); + return send_statustext(MAVLINK_IOC_SEND_TEXT_INFO, string); } int -Mavlink::send_statustext(enum MAV_SEVERITY severity, const char *string) +Mavlink::send_statustext_critical(const char *string) +{ + return send_statustext(MAVLINK_IOC_SEND_TEXT_CRITICAL, string); +} + +int +Mavlink::send_statustext_emergency(const char *string) +{ + return send_statustext(MAVLINK_IOC_SEND_TEXT_EMERGENCY, string); +} + +int +Mavlink::send_statustext(unsigned severity, const char *string) { const int len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN; mavlink_statustext_t statustext; - statustext.severity = severity; int i = 0; @@ -929,6 +941,19 @@ Mavlink::send_statustext(enum MAV_SEVERITY severity, const char *string) /* Enforce null termination */ statustext.text[i] = '\0'; + /* Map severity */ + switch (severity) { + case MAVLINK_IOC_SEND_TEXT_INFO: + statustext.severity = MAV_SEVERITY_INFO; + break; + case MAVLINK_IOC_SEND_TEXT_CRITICAL: + statustext.severity = MAV_SEVERITY_CRITICAL; + break; + case MAVLINK_IOC_SEND_TEXT_EMERGENCY: + statustext.severity = MAV_SEVERITY_EMERGENCY; + break; + } + mavlink_msg_statustext_send(_channel, statustext.severity, statustext.text); return OK; @@ -1449,7 +1474,7 @@ Mavlink::task_main(int argc, char *argv[]) int lb_ret = mavlink_logbuffer_read(&_logbuffer, &msg); if (lb_ret == OK) { - send_statustext(msg.text); + send_statustext(msg.severity, msg.text); } } } diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 1f4fb759f..acfc8b90e 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -157,9 +157,9 @@ public: */ int set_hil_enabled(bool hil_enabled); - void send_message(const mavlink_message_t *msg); + void send_message(const mavlink_message_t *msg); - void handle_message(const mavlink_message_t *msg); + void handle_message(const mavlink_message_t *msg); MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic); @@ -174,17 +174,43 @@ public: mavlink_channel_t get_channel(); - void configure_stream_threadsafe(const char *stream_name, float rate); + void configure_stream_threadsafe(const char *stream_name, float rate); bool _task_should_exit; /**< if true, mavlink task should exit */ int get_mavlink_fd() { return _mavlink_fd; } - int send_statustext(const char *string); - int send_statustext(enum MAV_SEVERITY severity, const char *string); - MavlinkStream * get_streams() const { return _streams; } + /** + * Send a status text with loglevel INFO + * + * @param string the message to send (will be capped by mavlink max string length) + */ + int send_statustext_info(const char *string); + + /** + * Send a status text with loglevel CRITICAL + * + * @param string the message to send (will be capped by mavlink max string length) + */ + int send_statustext_critical(const char *string); + + /** + * Send a status text with loglevel EMERGENCY + * + * @param string the message to send (will be capped by mavlink max string length) + */ + int send_statustext_emergency(const char *string); + + /** + * Send a status text with loglevel + * + * @param string the message to send (will be capped by mavlink max string length) + * @param severity the log level, one of + */ + int send_statustext(unsigned severity, const char *string); + MavlinkStream * get_streams() const { return _streams; } - float get_rate_mult(); + float get_rate_mult(); /* Functions for waiting to start transmission until message received. */ void set_has_received_messages(bool received_messages) { _received_messages = received_messages; } @@ -195,13 +221,13 @@ public: bool message_buffer_write(const void *ptr, int size); - void lockMessageBufferMutex(void) { pthread_mutex_lock(&_message_buffer_mutex); } - void unlockMessageBufferMutex(void) { pthread_mutex_unlock(&_message_buffer_mutex); } + void lockMessageBufferMutex(void) { pthread_mutex_lock(&_message_buffer_mutex); } + void unlockMessageBufferMutex(void) { pthread_mutex_unlock(&_message_buffer_mutex); } /** * Count a transmision error */ - void count_txerr(); + void count_txerr(); protected: Mavlink *next; -- cgit v1.2.3 From 7b768d11c3c8d57807495bf2abb324bb5f14aa14 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 14:31:09 +0200 Subject: Improve mission feedback, fix compile errors --- src/modules/mavlink/mavlink_mission.cpp | 58 +++++++++++++++++++-------------- src/modules/mavlink/mavlink_mission.h | 36 ++++++++++---------- 2 files changed, 52 insertions(+), 42 deletions(-) diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index ca01344d4..a62d34019 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -189,7 +189,7 @@ MavlinkMissionManager::send_mission_current(uint16_t seq) } else { if (_verbose) { warnx("WPM: Send MISSION_CURRENT ERROR: seq %u out of bounds", seq); } - _mavlink->send_statustext("ERROR: wp index out of bounds"); + _mavlink->send_statustext_critical("ERROR: wp index out of bounds"); } } @@ -238,7 +238,7 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t } else { send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); - _mavlink->send_statustext("#audio: Unable to read from micro SD"); + _mavlink->send_statustext_critical("Unable to read from micro SD"); if (_verbose) { warnx("WPM: Send MISSION_ITEM ERROR: could not read seq %u from dataman ID %i", seq, _dataman_id); } } @@ -262,7 +262,7 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1 if (_verbose) { warnx("WPM: Send MISSION_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system); } } else { - _mavlink->send_statustext("ERROR: Waypoint index exceeds list capacity"); + _mavlink->send_statustext_critical("ERROR: Waypoint index exceeds list capacity"); if (_verbose) { warnx("WPM: Send MISSION_REQUEST ERROR: seq %u exceeds list capacity", seq); } } @@ -314,7 +314,7 @@ MavlinkMissionManager::eventloop() /* check for timed-out operations */ if (_state != MAVLINK_WPM_STATE_IDLE && hrt_elapsed_time(&_time_last_recv) > _action_timeout) { - _mavlink->send_statustext("Operation timeout"); + _mavlink->send_statustext_critical("Operation timeout"); if (_verbose) { warnx("WPM: Last operation (state=%u) timed out, changing state to MAVLINK_WPM_STATE_IDLE", _state); } @@ -390,6 +390,8 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg) if (_verbose) { warnx("WPM: MISSION_ACK OK all items sent, switch to state IDLE"); } } else { + _mavlink->send_statustext_critical("WPM: ERR: not all items sent -> IDLE"); + if (_verbose) { warnx("WPM: MISSION_ACK ERROR: not all items sent, switch to state IDLE anyway"); } } @@ -397,7 +399,7 @@ MavlinkMissionManager::handle_mission_ack(const mavlink_message_t *msg) } } else { - _mavlink->send_statustext("REJ. WP CMD: partner id mismatch"); + _mavlink->send_statustext_critical("REJ. WP CMD: partner id mismatch"); if (_verbose) { warnx("WPM: MISSION_ACK ERROR: rejected, partner ID mismatch"); } } @@ -421,18 +423,20 @@ MavlinkMissionManager::handle_mission_set_current(const mavlink_message_t *msg) } else { if (_verbose) { warnx("WPM: MISSION_SET_CURRENT seq=%d ERROR", wpc.seq); } + + _mavlink->send_statustext_critical("WPM: WP CURR CMD: Error setting ID"); } } else { if (_verbose) { warnx("WPM: MISSION_SET_CURRENT seq=%d ERROR: not in list", wpc.seq); } - _mavlink->send_statustext("IGN WP CURR CMD: Not in list"); + _mavlink->send_statustext_critical("WPM: WP CURR CMD: Not in list"); } } else { if (_verbose) { warnx("WPM: MISSION_SET_CURRENT ERROR: busy"); } - _mavlink->send_statustext("IGN WP CURR CMD: Busy"); + _mavlink->send_statustext_critical("WPM: IGN WP CURR CMD: Busy"); } } } @@ -459,6 +463,8 @@ MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg) } else { if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST OK nothing to send, mission is empty"); } + + _mavlink->send_statustext_info("WPM: mission is empty"); } send_mission_count(msg->sysid, msg->compid, _count); @@ -466,7 +472,7 @@ MavlinkMissionManager::handle_mission_request_list(const mavlink_message_t *msg) } else { if (_verbose) { warnx("WPM: MISSION_REQUEST_LIST ERROR: busy"); } - _mavlink->send_statustext("IGN REQUEST LIST: Busy"); + _mavlink->send_statustext_critical("IGN REQUEST LIST: Busy"); } } } @@ -489,7 +495,7 @@ MavlinkMissionManager::handle_mission_request(const mavlink_message_t *msg) _transfer_seq++; - } else if (wpr.seq == _transfer_seq - 1 && wpr.seq >= 0) { + } else if (wpr.seq == _transfer_seq - 1) { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST seq %u from ID %u (again)", wpr.seq, msg->sysid); } } else { @@ -506,36 +512,36 @@ MavlinkMissionManager::handle_mission_request(const mavlink_message_t *msg) _state = MAVLINK_WPM_STATE_IDLE; send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); - _mavlink->send_statustext("REJ. WP CMD: Req. WP was unexpected"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected"); return; } /* double check bounds in case of items count changed */ - if (wpr.seq >= 0 && wpr.seq < _count) { + if (wpr.seq < _count) { send_mission_item(_transfer_partner_sysid, _transfer_partner_compid, wpr.seq); } else { - if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u out of bound [0, %u]", wpr.seq, msg->sysid, wpr.seq, _count - 1); } + if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: seq %u out of bound [%u, %u]", (unsigned)wpr.seq, (unsigned)wpr.seq, (unsigned)_count - 1); } _state = MAVLINK_WPM_STATE_IDLE; send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); - _mavlink->send_statustext("REJ. WP CMD: Req. WP was unexpected"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: Req. WP was unexpected"); } } else if (_state == MAVLINK_WPM_STATE_IDLE) { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: no transfer"); } - _mavlink->send_statustext("IGN MISSION_ITEM_REQUEST: No transfer"); + _mavlink->send_statustext_critical("IGN MISSION_ITEM_REQUEST: No active transfer"); } else { if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: busy (state %d).", _state); } - _mavlink->send_statustext("REJ. WP CMD: Busy"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy"); } } else { - _mavlink->send_statustext("REJ. WP CMD: partner id mismatch"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: partner id mismatch"); if (_verbose) { warnx("WPM: MISSION_ITEM_REQUEST ERROR: rejected, partner ID mismatch"); } } @@ -565,7 +571,7 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) /* alternate dataman ID anyway to let navigator know about changes */ update_active_mission(_dataman_id == 0 ? 1 : 0, 0, 0); - _mavlink->send_statustext("WP COUNT 0: CLEAR MISSION"); + _mavlink->send_statustext_info("WPM: COUNT 0: CLEAR MISSION"); // TODO send ACK? return; @@ -588,19 +594,19 @@ MavlinkMissionManager::handle_mission_count(const mavlink_message_t *msg) /* looks like our MISSION_REQUEST was lost, try again */ if (_verbose) { warnx("WPM: MISSION_COUNT %u from ID %u (again)", wpc.count, msg->sysid); } - _mavlink->send_statustext("WP CMD OK AGAIN"); + _mavlink->send_statustext_info("WP CMD OK TRY AGAIN"); } else { if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, already receiving seq %u", _transfer_seq); } - _mavlink->send_statustext("REJ. WP CMD: Busy"); + _mavlink->send_statustext_critical("WPM: REJ. CMD: Busy"); return; } } else { if (_verbose) { warnx("WPM: MISSION_COUNT ERROR: busy, state %i", _state); } - _mavlink->send_statustext("IGN MISSION_COUNT: Busy"); + _mavlink->send_statustext_critical("WPM: IGN MISSION_COUNT: Busy"); return; } @@ -629,13 +635,13 @@ MavlinkMissionManager::handle_mission_item(const mavlink_message_t *msg) } else if (_state == MAVLINK_WPM_STATE_IDLE) { if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: no transfer"); } - _mavlink->send_statustext("IGN MISSION_ITEM: No transfer"); + _mavlink->send_statustext_critical("IGN MISSION_ITEM: No transfer"); return; } else { if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: busy, state %i", _state); } - _mavlink->send_statustext("IGN MISSION_ITEM: Busy"); + _mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy"); return; } @@ -645,6 +651,8 @@ MavlinkMissionManager::handle_mission_item(const mavlink_message_t *msg) if (ret != OK) { if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: seq %u invalid item", wp.seq); } + _mavlink->send_statustext_critical("IGN MISSION_ITEM: Busy"); + send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, ret); _state = MAVLINK_WPM_STATE_IDLE; return; @@ -656,7 +664,7 @@ MavlinkMissionManager::handle_mission_item(const mavlink_message_t *msg) if (_verbose) { warnx("WPM: MISSION_ITEM ERROR: error writing seq %u to dataman ID %i", wp.seq, _transfer_dataman_id); } send_mission_ack(_transfer_partner_sysid, _transfer_partner_compid, MAV_MISSION_ERROR); - _mavlink->send_statustext("#audio: Unable to write on micro SD"); + _mavlink->send_statustext_critical("Unable to write on micro SD"); _state = MAVLINK_WPM_STATE_IDLE; return; } @@ -674,6 +682,8 @@ MavlinkMissionManager::handle_mission_item(const mavlink_message_t *msg) /* got all new mission items successfully */ if (_verbose) { warnx("WPM: MISSION_ITEM got all %u items, current_seq=%u, changing state to MAVLINK_WPM_STATE_IDLE", _transfer_count, _transfer_current_seq); } + _mavlink->send_statustext_info("WPM: Transfer complete."); + _state = MAVLINK_WPM_STATE_IDLE; if (update_active_mission(_transfer_dataman_id, _transfer_count, _transfer_current_seq) == OK) { @@ -712,7 +722,7 @@ MavlinkMissionManager::handle_mission_clear_all(const mavlink_message_t *msg) } } else { - _mavlink->send_statustext("IGN WP CLEAR CMD: Busy"); + _mavlink->send_statustext_critical("WPM: IGN CLEAR CMD: Busy"); if (_verbose) { warnx("WPM: CLEAR_ALL IGNORED: busy"); } } diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h index d8695cf83..1964a45e8 100644 --- a/src/modules/mavlink/mavlink_mission.h +++ b/src/modules/mavlink/mavlink_mission.h @@ -142,35 +142,35 @@ public: void set_verbose(bool v) { _verbose = v; } private: - Mavlink* _mavlink; + Mavlink* _mavlink; mavlink_channel_t _channel; - uint8_t _comp_id; + uint8_t _comp_id; - enum MAVLINK_WPM_STATES _state; ///< Current state + enum MAVLINK_WPM_STATES _state; ///< Current state - uint64_t _time_last_recv; - uint64_t _time_last_sent; + uint64_t _time_last_recv; + uint64_t _time_last_sent; - uint32_t _action_timeout; - uint32_t _retry_timeout; - unsigned _max_count; ///< Maximal count of mission items + uint32_t _action_timeout; + uint32_t _retry_timeout; + unsigned _max_count; ///< Maximal count of mission items - int _dataman_id; ///< Dataman storage ID for active mission - unsigned _count; ///< Count of items in active mission - int _current_seq; ///< Current item sequence in active mission + int _dataman_id; ///< Dataman storage ID for active mission + unsigned _count; ///< Count of items in active mission + int _current_seq; ///< Current item sequence in active mission int _transfer_dataman_id; ///< Dataman storage ID for current transmission - unsigned _transfer_count; ///< Items count in current transmission - int _transfer_seq; ///< Item sequence in current transmission - int _transfer_current_seq; ///< Current item ID for current transmission (-1 means not initialized) - uint8_t _transfer_partner_sysid; ///< Partener SysID for current transmission - uint8_t _transfer_partner_compid; ///< Partner ComponentID for current transmission + unsigned _transfer_count; ///< Items count in current transmission + unsigned _transfer_seq; ///< Item sequence in current transmission + unsigned _transfer_current_seq; ///< Current item ID for current transmission (-1 means not initialized) + uint8_t _transfer_partner_sysid; ///< Partener SysID for current transmission + uint8_t _transfer_partner_compid; ///< Partner ComponentID for current transmission int _offboard_mission_sub; int _mission_result_sub; - orb_advert_t _offboard_mission_pub; + orb_advert_t _offboard_mission_pub; - MavlinkRateLimiter _slow_rate_limiter; + MavlinkRateLimiter _slow_rate_limiter; bool _verbose; }; -- cgit v1.2.3 From e64a28e736224da5d1db8e3477eeeffc0b3b1f6c Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 12 Jul 2014 17:34:36 +0400 Subject: Building UAVCAN without run-time checks. This saves 9.5KB of flash and reduces CPU usage. --- src/modules/uavcan/module.mk | 10 +++++----- uavcan | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index 2c75944d4..1ef6f0cfa 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -40,9 +40,9 @@ MODULE_COMMAND = uavcan MAXOPTIMIZATION = -Os -SRCS += uavcan_main.cpp \ - uavcan_clock.cpp \ - esc_controller.cpp \ +SRCS += uavcan_main.cpp \ + uavcan_clock.cpp \ + esc_controller.cpp \ gnss_receiver.cpp # @@ -53,7 +53,7 @@ SRCS += $(LIBUAVCAN_SRC) INCLUDE_DIRS += $(LIBUAVCAN_INC) # Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile # because this platform lacks most of the standard library and STL. Hence we need to force C++03 mode. -override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 +override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 -DUAVCAN_NO_ASSERTIONS # # libuavcan drivers for STM32 @@ -68,7 +68,7 @@ override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM # TODO: Add make target for this, or invoke dsdlc manually. # The second option assumes that the generated headers shall be saved # under the version control, which may be undesirable. -# The first option requires python3 and python3-mako for the sources to be built. +# The first option requires any Python and the Python Mako library for the sources to be built. # $(info $(shell $(LIBUAVCAN_DSDLC) $(UAVCAN_DSDL_DIR))) INCLUDE_DIRS += dsdlc_generated diff --git a/uavcan b/uavcan index f66c1a7de..af065e9ca 160000 --- a/uavcan +++ b/uavcan @@ -1 +1 @@ -Subproject commit f66c1a7de3076ff956bdf159dc3a166cbffe6089 +Subproject commit af065e9ca9e3ba9100c125d3ab739313d0500ca8 -- cgit v1.2.3 From a0d150332ab67dbc501b10fa8adb97d91a79f23c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 15:39:04 +0200 Subject: Add note to param about tubes --- src/modules/sensors/sensor_params.c | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 8f6e7abe6..38b190761 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -207,6 +207,9 @@ PARAM_DEFINE_FLOAT(SENS_DPRES_OFF, 0.0f); * this number defines the (linear) conversion from voltage * to Pascal (pa). For the MPXV7002DP this is 1000. * + * NOTE: If the sensor always registers zero, try switching + * the static and dynamic tubes. + * * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(SENS_DPRES_ANSC, 0); -- cgit v1.2.3 From 024c8213a10d83743caea21206d21f3de497b18a Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 12 Jul 2014 17:45:05 +0400 Subject: Fixed check_submodules.sh for UAVCAN --- Tools/check_submodules.sh | 16 ++++++++++++---- 1 file changed, 12 insertions(+), 4 deletions(-) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index abe3088c7..8fd9a8f00 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -46,14 +46,22 @@ else fi -if [ -d uavcan/libuavcan_drivers ]; +if [ -d uavcan ] then - STATUSRETVAL=$(git status --porcelain | grep -i uavcan) - if [ "$STATUSRETVAL" == "" ]; then + STATUSRETVAL=$(git submodule summary | grep -A20 -i uavcan | grep "<") + if [ -z "$STATUSRETVAL" ] + then echo "Checked uavcan submodule, correct version found" else - echo "uavcan sub repo not at correct version. Try 'make updatesubmodules'" + echo "" + echo "" + echo "uavcan sub repo not at correct version. Try 'git submodule update'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" + echo "" + echo "" + echo "New commits required:" + echo "$(git submodule summary)" + echo "" exit 1 fi else -- cgit v1.2.3 From 45617e9f4385e80846c571b237e220216192d6ce Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 16:09:14 +0200 Subject: Airspeed calibration improvement, enforce correct pitot order --- src/modules/commander/airspeed_calibration.cpp | 137 ++++++++++++++++++++----- src/modules/ekf_att_pos_estimator/InertialNav | 1 + 2 files changed, 112 insertions(+), 26 deletions(-) create mode 160000 src/modules/ekf_att_pos_estimator/InertialNav diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 7599fc777..a1a20abc9 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -64,14 +64,12 @@ int do_airspeed_calibration(int mavlink_fd) { /* give directions */ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name); - mavlink_log_info(mavlink_fd, "ensure airspeed sensor is not registering wind"); - const int calibration_count = 2000; + const unsigned calibration_count = 2000; int diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); struct differential_pressure_s diff_pres; - int calibration_counter = 0; float diff_pres_offset = 0.0f; /* Reset sensor parameters */ @@ -105,29 +103,58 @@ int do_airspeed_calibration(int mavlink_fd) } } - while (calibration_counter < calibration_count) { + for (unsigned i = 0; i < (sizeof(diff_pres_offset) / sizeof(diff_pres_offset[0])); i++) { - /* wait blocking for new data */ - struct pollfd fds[1]; - fds[0].fd = diff_pres_sub; - fds[0].events = POLLIN; + unsigned calibration_counter = 0; - int poll_ret = poll(fds, 1, 1000); + if (i == 0) { + mavlink_log_critical(mavlink_fd, "Ensure sensor is not measuring wind"); + usleep(500 * 1000); + } - if (poll_ret) { - orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); - diff_pres_offset += diff_pres.differential_pressure_raw_pa; - calibration_counter++; + float diff_pres_offset = 0.0f; - if (calibration_counter % (calibration_count / 20) == 0) { - mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count); - } + while (calibration_counter < calibration_count) { - } else if (poll_ret == 0) { - /* any poll failure for 1s is a reason to abort */ - mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); - close(diff_pres_sub); - return ERROR; + /* wait blocking for new data */ + struct pollfd fds[1]; + fds[0].fd = diff_pres_sub; + fds[0].events = POLLIN; + + int poll_ret = poll(fds, 1, 1000); + + if (poll_ret) { + orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); + + if (i > 0) { + + if (calc_indicated_airspeed(fabsf(diff_pres.differential_pressure_raw_pa)) < 10.0f) { + mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot"); + usleep(5000 * 1000); + continue; + } + + /* do not log negative values in the second go */ + if ((diff_pres_offset / calibration_counter) < calc_indicated_airspeed(-5.0f)) { + mavlink_log_critical(mavlink_fd, "Negative val: swap static<->dynamic ports,restart"); + close(diff_pres_sub); + return ERROR; + } + } + + diff_pres_offset += diff_pres.differential_pressure_raw_pa; + calibration_counter++; + + if (calibration_counter % (calibration_count / 20) == 0) { + mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count / 2); + } + + } else if (poll_ret == 0) { + /* any poll failure for 1s is a reason to abort */ + mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); + close(diff_pres_sub); + return ERROR; + } } } @@ -151,14 +178,72 @@ int do_airspeed_calibration(int mavlink_fd) return ERROR; } - mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name); - tune_neutral(true); - close(diff_pres_sub); - return OK; - } else { mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name); close(diff_pres_sub); return ERROR; } + + /* wait 500 ms to ensure parameter propagated through the system */ + usleep(500 * 1000); + + calibration_counter = 0; + diff_pres_offset = 0.0f; + + /* just take a few samples and make sure pitot tubes are not reversed */ + while (calibration_counter < 50) { + + /* wait blocking for new data */ + struct pollfd fds[1]; + fds[0].fd = diff_pres_sub; + fds[0].events = POLLIN; + + int poll_ret = poll(fds, 1, 1000); + + if (poll_ret) { + orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); + + diff_pres_offset += diff_pres.differential_pressure_raw_pa; + calibration_counter++; + + float curr_avg = (diff_pres_offset / calibration_counter); + + if (calc_indicated_airspeed(fabsf(curr_avg)) < 10.0f) { + mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot"); + usleep(5000 * 1000); + continue; + } + + /* do not log negative values in the second go */ + if (curr_avg < calc_indicated_airspeed(-5.0f)) { + mavlink_log_critical(mavlink_fd, "Negative val: swap static<->dynamic ports,restart"); + close(diff_pres_sub); + + /* the user setup is wrong, wipe the calibration to force a proper re-calibration */ + + diff_pres_offset = 0.0f; + if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) { + mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG); + close(diff_pres_sub); + return ERROR; + } + + /* save */ + (void)param_save_default(); + + return ERROR; + } + + } else if (poll_ret == 0) { + /* any poll failure for 1s is a reason to abort */ + mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); + close(diff_pres_sub); + return ERROR; + } + } + + mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name); + tune_neutral(true); + close(diff_pres_sub); + return OK; } diff --git a/src/modules/ekf_att_pos_estimator/InertialNav b/src/modules/ekf_att_pos_estimator/InertialNav new file mode 160000 index 000000000..8b65d755b --- /dev/null +++ b/src/modules/ekf_att_pos_estimator/InertialNav @@ -0,0 +1 @@ +Subproject commit 8b65d755b8c4834f90a323172c25d91c45068e21 -- cgit v1.2.3 From 4dc65d6f09bcf891ee228ef9fc6b576251fc8b65 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 16:09:49 +0200 Subject: NuttX I2C fixes --- NuttX | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/NuttX b/NuttX index 2a94cc8e5..7e1b97bcf 160000 --- a/NuttX +++ b/NuttX @@ -1 +1 @@ -Subproject commit 2a94cc8e5babb7d5661aedc09201239d39644332 +Subproject commit 7e1b97bcf10d8495169eec355988ca5890bfd5df -- cgit v1.2.3 From 93d444d1aade59b5e88f41b71c842a00ab950c64 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Jul 2014 21:09:12 +1000 Subject: device: added a _device_id to all drivers this device ID identifies a specific device via the tuple of (bus, bus type, address, devtype). This allows device specific configuration data to be stored along with a device ID, so the code can know when the user has changed device configuration (such as removing an external compass), and either invalidate the device configuration or force the user to re-calibrate --- src/drivers/device/device.cpp | 12 ++++++++++++ src/drivers/device/device.h | 25 +++++++++++++++++++++++++ src/drivers/device/i2c.cpp | 8 +++++++- src/drivers/device/spi.cpp | 6 ++++++ src/drivers/drv_device.h | 7 +++++++ 5 files changed, 57 insertions(+), 1 deletion(-) diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp index 683455149..f1f777dce 100644 --- a/src/drivers/device/device.cpp +++ b/src/drivers/device/device.cpp @@ -42,6 +42,7 @@ #include #include #include +#include namespace device { @@ -93,6 +94,13 @@ Device::Device(const char *name, _irq_attached(false) { sem_init(&_lock, 0, 1); + + /* setup a default device ID. When bus_type is UNKNOWN the + other fields are invalid */ + _device_id.devid_s.bus_type = DeviceBusType_UNKNOWN; + _device_id.devid_s.bus = 0; + _device_id.devid_s.address = 0; + _device_id.devid_s.devtype = 0; } Device::~Device() @@ -238,6 +246,10 @@ Device::write(unsigned offset, void *data, unsigned count) int Device::ioctl(unsigned operation, unsigned &arg) { + switch (operation) { + case DEVIOCGDEVICEID: + return (int)_device_id.devid; + } return -ENODEV; } diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h index d99f22922..c98386eb0 100644 --- a/src/drivers/device/device.h +++ b/src/drivers/device/device.h @@ -124,9 +124,34 @@ public: */ virtual int ioctl(unsigned operation, unsigned &arg); + /* + device bus types for DEVID + */ + enum DeviceBusType { + DeviceBusType_UNKNOWN = 0, + DeviceBusType_I2C = 1, + DeviceBusType_SPI = 2 + }; + + /* + broken out + */ + struct DeviceStructure { + enum DeviceBusType bus_type; + uint8_t bus; // which instance of the bus type + uint8_t address; // address on the bus (eg. I2C address) + uint8_t devtype; // device class specific device type + }; + + union DeviceId { + struct DeviceStructure devid_s; + uint32_t devid; + }; + protected: const char *_name; /**< driver name */ bool _debug_enabled; /**< if true, debug messages are printed */ + union DeviceId _device_id; /**< device identifier information */ /** * Constructor diff --git a/src/drivers/device/i2c.cpp b/src/drivers/device/i2c.cpp index a416801eb..286778c01 100644 --- a/src/drivers/device/i2c.cpp +++ b/src/drivers/device/i2c.cpp @@ -62,6 +62,12 @@ I2C::I2C(const char *name, _frequency(frequency), _dev(nullptr) { + // fill in _device_id fields for a I2C device + _device_id.devid_s.bus_type = DeviceBusType_I2C; + _device_id.devid_s.bus = bus; + _device_id.devid_s.address = address; + // devtype needs to be filled in by the driver + _device_id.devid_s.devtype = 0; } I2C::~I2C() @@ -201,4 +207,4 @@ I2C::transfer(i2c_msg_s *msgv, unsigned msgs) return ret; } -} // namespace device \ No newline at end of file +} // namespace device diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp index 1ab1dc699..200acac05 100644 --- a/src/drivers/device/spi.cpp +++ b/src/drivers/device/spi.cpp @@ -75,6 +75,12 @@ SPI::SPI(const char *name, _dev(nullptr), _bus(bus) { + // fill in _device_id fields for a SPI device + _device_id.devid_s.bus_type = DeviceBusType_SPI; + _device_id.devid_s.bus = bus; + _device_id.devid_s.address = (uint8_t)device; + // devtype needs to be filled in by the driver + _device_id.devid_s.devtype = 0; } SPI::~SPI() diff --git a/src/drivers/drv_device.h b/src/drivers/drv_device.h index b310beb74..19d55cef3 100644 --- a/src/drivers/drv_device.h +++ b/src/drivers/drv_device.h @@ -59,4 +59,11 @@ /** check publication block status */ #define DEVIOCGPUBBLOCK _DEVICEIOC(1) +/** + * Return device ID, to enable matching of configuration parameters + * (such as compass offsets) to specific sensors + */ +#define DEVIOCGDEVICEID _DEVICEIOC(2) + + #endif /* _DRV_DEVICE_H */ -- cgit v1.2.3 From a2739707bb18a1aed0dcc0f809badce606aaed51 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Jul 2014 21:09:26 +1000 Subject: drv_mag: added devtypes for magnetometers --- src/drivers/drv_mag.h | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h index 06107bd3d..a259ac9c0 100644 --- a/src/drivers/drv_mag.h +++ b/src/drivers/drv_mag.h @@ -81,6 +81,13 @@ struct mag_scale { */ ORB_DECLARE(sensor_mag); + +/* + * mag device types, for _device_id + */ +#define DRV_MAG_DEVTYPE_HMC5883 1 +#define DRV_MAG_DEVTYPE_LSM303D 2 + /* * ioctl() definitions */ -- cgit v1.2.3 From 30a6a3d0b6cc53fef45264d140ce3026d986af83 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Jul 2014 21:09:38 +1000 Subject: hmc5883: setup device type --- src/drivers/hmc5883/hmc5883.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index c2e4700d8..cd2b5c48e 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -341,6 +341,8 @@ HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) : _bus(bus), _rotation(rotation) { + _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883; + // enable debug() calls _debug_enabled = false; -- cgit v1.2.3 From c6b0dc1ee85348d8dbe398457e9631e095ec9c61 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Jul 2014 21:09:47 +1000 Subject: lsm303d: setup device type --- src/drivers/lsm303d/lsm303d.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 7ba0fcc88..45e775055 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -530,6 +530,8 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota _last_log_alarm_us(0), _rotation(rotation) { + _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LSM303D; + // enable debug() calls _debug_enabled = true; -- cgit v1.2.3 From 6cffa948fe6edc1e58b7d55acf119e8793461510 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 8 Jul 2014 21:37:45 +1000 Subject: device: pass CDev::ioctl() to superclass this allows DEVIOCGDEVICEID to work. --- src/drivers/device/cdev.cpp | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/src/drivers/device/cdev.cpp b/src/drivers/device/cdev.cpp index 6e2ebb1f7..39fb89501 100644 --- a/src/drivers/device/cdev.cpp +++ b/src/drivers/device/cdev.cpp @@ -268,6 +268,13 @@ CDev::ioctl(struct file *filp, int cmd, unsigned long arg) break; } + /* try the superclass. The different ioctl() function form + * means we need to copy arg */ + unsigned arg2 = arg; + int ret = Device::ioctl(cmd, arg2); + if (ret != -ENODEV) + return ret; + return -ENOTTY; } -- cgit v1.2.3 From 20cd5026d817a4f17b96906d1c93fc3cbaa498dd Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 11 Jul 2014 09:49:43 +1000 Subject: device: use bitfields to keep DeviceStructure small this keeps it small enough to fit in a float, which makes it possible to see the full value in a MAVLink tlog Conflicts: mavlink/include/mavlink/v1.0 --- src/drivers/device/device.h | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h index c98386eb0..7df234cab 100644 --- a/src/drivers/device/device.h +++ b/src/drivers/device/device.h @@ -134,11 +134,14 @@ public: }; /* - broken out + broken out device elements. The bitfields are used to keep + the overall value small enough to fit in a float accurately, + which makes it possible to transport over the MAVLink + parameter protocol without loss of information. */ struct DeviceStructure { - enum DeviceBusType bus_type; - uint8_t bus; // which instance of the bus type + enum DeviceBusType bus_type:3; + uint8_t bus:5; // which instance of the bus type uint8_t address; // address on the bus (eg. I2C address) uint8_t devtype; // device class specific device type }; -- cgit v1.2.3 From 8a3a87331da2077cd1da4c3da8fe2743f188a4a4 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 11 Jul 2014 22:21:53 +1000 Subject: mpu6000: fixed internal/external mixup in pointers Thanks to Emile for spotting this! Conflicts: mavlink/include/mavlink/v1.0 --- src/drivers/mpu6000/mpu6000.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 5668b0865..1b3a96a0d 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -1442,7 +1442,7 @@ void start(bool external_bus, enum Rotation rotation) { int fd; - MPU6000 **g_dev_ptr = external_bus?&g_dev_int:&g_dev_ext; + MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int; const char *path_accel = external_bus?MPU_DEVICE_PATH_ACCEL_EXT:MPU_DEVICE_PATH_ACCEL; const char *path_gyro = external_bus?MPU_DEVICE_PATH_GYRO_EXT:MPU_DEVICE_PATH_GYRO; @@ -1595,7 +1595,7 @@ reset(bool external_bus) void info(bool external_bus) { - MPU6000 **g_dev_ptr = external_bus?&g_dev_int:&g_dev_ext; + MPU6000 **g_dev_ptr = external_bus?&g_dev_ext:&g_dev_int; if (*g_dev_ptr == nullptr) errx(1, "driver not running"); -- cgit v1.2.3 From b288b010f12213a4388b627bce7fd6cb4cdedea5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 18:42:00 +0200 Subject: tests, drive by: Fix double comparison, use reasonable margin based on context of test --- src/systemcmds/tests/test_bson.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/systemcmds/tests/test_bson.c b/src/systemcmds/tests/test_bson.c index 6130fe763..12d598df4 100644 --- a/src/systemcmds/tests/test_bson.c +++ b/src/systemcmds/tests/test_bson.c @@ -40,6 +40,7 @@ #include #include #include +#include #include #include @@ -123,7 +124,7 @@ decode_callback(bson_decoder_t decoder, void *private, bson_node_t node) warnx("FAIL: decoder: double1 type %d, expected %d", node->type, BSON_DOUBLE); return 1; } - if (node->d != sample_double) { + if (fabs(node->d - sample_double) > 1e-12) { warnx("FAIL: decoder: double1 value %f, expected %f", node->d, sample_double); return 1; } -- cgit v1.2.3 From ffebe45c4ce6cb248314141d91abcb74fbf9174e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 18:42:25 +0200 Subject: mavlink: Handle unhandled enum cases --- src/modules/mavlink/mavlink_messages.cpp | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index c7ad605c5..7c864f127 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -170,6 +170,8 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set break; case NAVIGATION_STATE_LAND: + /* fallthrough */ + case NAVIGATION_STATE_DESCEND: *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED | MAV_MODE_FLAG_STABILIZE_ENABLED | MAV_MODE_FLAG_GUIDED_ENABLED; @@ -190,6 +192,17 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_MANUAL; break; + case NAVIGATION_STATE_OFFBOARD: + *mavlink_base_mode |= MAV_MODE_FLAG_AUTO_ENABLED + | MAV_MODE_FLAG_STABILIZE_ENABLED + | MAV_MODE_FLAG_GUIDED_ENABLED; + custom_mode.main_mode = PX4_CUSTOM_MAIN_MODE_OFFBOARD; + break; + + case NAVIGATION_STATE_MAX: + /* this is an unused case, ignore */ + break; + } *mavlink_custom_mode = custom_mode.data; -- cgit v1.2.3 From 0144a7dacfdb398c6133a9bf2df35facdbdfe6e3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 18:43:09 +0200 Subject: mavlink: Optimize to native types where possible, move things to optimize alignment --- src/modules/mavlink/mavlink_mission.cpp | 6 +++--- src/modules/mavlink/mavlink_mission.h | 11 ++++++----- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index a62d34019..068774c47 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -61,8 +61,6 @@ static const int ERROR = -1; MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : _mavlink(mavlink), - _channel(mavlink->get_channel()), - _comp_id(MAV_COMP_ID_MISSIONPLANNER), _state(MAVLINK_WPM_STATE_IDLE), _time_last_recv(0), _time_last_sent(0), @@ -82,7 +80,9 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : _mission_result_sub(-1), _offboard_mission_pub(-1), _slow_rate_limiter(2000000.0f / mavlink->get_rate_mult()), - _verbose(false) + _verbose(false), + _channel(mavlink->get_channel()), + _comp_id(MAV_COMP_ID_MISSIONPLANNER) { _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission)); _mission_result_sub = orb_subscribe(ORB_ID(mission_result)); diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h index 1964a45e8..f63c32f24 100644 --- a/src/modules/mavlink/mavlink_mission.h +++ b/src/modules/mavlink/mavlink_mission.h @@ -143,8 +143,6 @@ public: private: Mavlink* _mavlink; - mavlink_channel_t _channel; - uint8_t _comp_id; enum MAVLINK_WPM_STATES _state; ///< Current state @@ -153,7 +151,7 @@ private: uint32_t _action_timeout; uint32_t _retry_timeout; - unsigned _max_count; ///< Maximal count of mission items + unsigned _max_count; ///< Maximum number of mission items int _dataman_id; ///< Dataman storage ID for active mission unsigned _count; ///< Count of items in active mission @@ -163,8 +161,8 @@ private: unsigned _transfer_count; ///< Items count in current transmission unsigned _transfer_seq; ///< Item sequence in current transmission unsigned _transfer_current_seq; ///< Current item ID for current transmission (-1 means not initialized) - uint8_t _transfer_partner_sysid; ///< Partener SysID for current transmission - uint8_t _transfer_partner_compid; ///< Partner ComponentID for current transmission + unsigned _transfer_partner_sysid; ///< Partner system ID for current transmission + unsigned _transfer_partner_compid; ///< Partner component ID for current transmission int _offboard_mission_sub; int _mission_result_sub; @@ -173,4 +171,7 @@ private: MavlinkRateLimiter _slow_rate_limiter; bool _verbose; + + mavlink_channel_t _channel; + uint8_t _comp_id; }; -- cgit v1.2.3 From 005dd206d17920761f8e27b21d54770da59faa13 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 12 Jul 2014 09:51:22 +1000 Subject: hmc5883: periodically check the config and range registers this copes with I2C comms errors causing the range or config registers to become corrupted, leading to bad reading. This is easily reproducible with a 1.3m I2C cable in the same run of cable as a GPS UART cable. The error happens every half hour or so. Conflicts: mavlink/include/mavlink/v1.0 src/drivers/hmc5883/hmc5883.cpp --- src/drivers/hmc5883/hmc5883.cpp | 141 ++++++++++++++++++++++++++++++++-------- 1 file changed, 114 insertions(+), 27 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index cd2b5c48e..4aef43102 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -166,6 +166,8 @@ private: perf_counter_t _sample_perf; perf_counter_t _comms_errors; perf_counter_t _buffer_overflows; + perf_counter_t _range_errors; + perf_counter_t _conf_errors; /* status reporting */ bool _sensor_ok; /**< sensor was found and reports ok */ @@ -176,6 +178,9 @@ private: struct mag_report _last_report; /**< used for info() */ + uint8_t _range_bits; + uint8_t _conf_reg; + /** * Test whether the device supported by the driver is present at a * specific address. @@ -233,6 +238,23 @@ private: */ int set_range(unsigned range); + /** + * check the sensor range. + * + * checks that the range of the sensor is correctly set, to + * cope with communication errors causing the range to change + */ + void check_range(void); + + /** + * check the sensor configuration. + * + * checks that the config of the sensor is correctly set, to + * cope with communication errors causing the configuration to + * change + */ + void check_conf(void); + /** * Perform a poll cycle; collect from the previous measurement * and start a new one. @@ -336,10 +358,15 @@ HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) : _sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")), _comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "hmc5883_buffer_overflows")), + _range_errors(perf_alloc(PC_COUNT, "hmc5883_range_errors")), + _conf_errors(perf_alloc(PC_COUNT, "hmc5883_conf_errors")), _sensor_ok(false), _calibrated(false), _bus(bus), - _rotation(rotation) + _rotation(rotation), + _last_report{0}, + _range_bits(0), + _conf_reg(0) { _device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883; @@ -373,6 +400,8 @@ HMC5883::~HMC5883() perf_free(_sample_perf); perf_free(_comms_errors); perf_free(_buffer_overflows); + perf_free(_range_errors); + perf_free(_conf_errors); } int @@ -403,45 +432,43 @@ out: int HMC5883::set_range(unsigned range) { - uint8_t range_bits; - if (range < 1) { - range_bits = 0x00; + _range_bits = 0x00; _range_scale = 1.0f / 1370.0f; _range_ga = 0.88f; } else if (range <= 1) { - range_bits = 0x01; + _range_bits = 0x01; _range_scale = 1.0f / 1090.0f; _range_ga = 1.3f; } else if (range <= 2) { - range_bits = 0x02; + _range_bits = 0x02; _range_scale = 1.0f / 820.0f; _range_ga = 1.9f; } else if (range <= 3) { - range_bits = 0x03; + _range_bits = 0x03; _range_scale = 1.0f / 660.0f; _range_ga = 2.5f; } else if (range <= 4) { - range_bits = 0x04; + _range_bits = 0x04; _range_scale = 1.0f / 440.0f; _range_ga = 4.0f; } else if (range <= 4.7f) { - range_bits = 0x05; + _range_bits = 0x05; _range_scale = 1.0f / 390.0f; _range_ga = 4.7f; } else if (range <= 5.6f) { - range_bits = 0x06; + _range_bits = 0x06; _range_scale = 1.0f / 330.0f; _range_ga = 5.6f; } else { - range_bits = 0x07; + _range_bits = 0x07; _range_scale = 1.0f / 230.0f; _range_ga = 8.1f; } @@ -451,7 +478,7 @@ int HMC5883::set_range(unsigned range) /* * Send the command to set the range */ - ret = write_reg(ADDR_CONF_B, (range_bits << 5)); + ret = write_reg(ADDR_CONF_B, (_range_bits << 5)); if (OK != ret) perf_count(_comms_errors); @@ -462,7 +489,53 @@ int HMC5883::set_range(unsigned range) if (OK != ret) perf_count(_comms_errors); - return !(range_bits_in == (range_bits << 5)); + return !(range_bits_in == (_range_bits << 5)); +} + +/** + check that the range register has the right value. This is done + periodically to cope with I2C bus noise causing the range of the + compass changing. + */ +void HMC5883::check_range(void) +{ + int ret; + + uint8_t range_bits_in; + ret = read_reg(ADDR_CONF_B, range_bits_in); + if (OK != ret) { + perf_count(_comms_errors); + return; + } + if (range_bits_in != (_range_bits<<5)) { + perf_count(_range_errors); + ret = write_reg(ADDR_CONF_B, (_range_bits << 5)); + if (OK != ret) + perf_count(_comms_errors); + } +} + +/** + check that the configuration register has the right value. This is + done periodically to cope with I2C bus noise causing the + configuration of the compass to change. + */ +void HMC5883::check_conf(void) +{ + int ret; + + uint8_t conf_reg_in; + ret = read_reg(ADDR_CONF_A, conf_reg_in); + if (OK != ret) { + perf_count(_comms_errors); + return; + } + if (conf_reg_in != _conf_reg) { + perf_count(_conf_errors); + ret = write_reg(ADDR_CONF_A, _conf_reg); + if (OK != ret) + perf_count(_comms_errors); + } } int @@ -796,7 +869,7 @@ HMC5883::collect() } report; int ret = -EIO; uint8_t cmd; - + uint8_t check_counter; perf_begin(_sample_perf); struct mag_report new_report; @@ -895,6 +968,21 @@ HMC5883::collect() /* notify anyone waiting for data */ poll_notify(POLLIN); + /* + periodically check the range register and configuration + registers. With a bad I2C cable it is possible for the + registers to become corrupt, leading to bad readings. It + doesn't happen often, but given the poor cables some + vehicles have it is worth checking for. + */ + check_counter = perf_event_count(_sample_perf) % 256; + if (check_counter == 0) { + check_range(); + } + if (check_counter == 128) { + check_conf(); + } + ret = OK; out: @@ -1168,25 +1256,24 @@ int HMC5883::set_excitement(unsigned enable) { int ret; /* arm the excitement strap */ - uint8_t conf_reg; - ret = read_reg(ADDR_CONF_A, conf_reg); + ret = read_reg(ADDR_CONF_A, _conf_reg); if (OK != ret) perf_count(_comms_errors); if (((int)enable) < 0) { - conf_reg |= 0x01; + _conf_reg |= 0x01; } else if (enable > 0) { - conf_reg |= 0x02; + _conf_reg |= 0x02; } else { - conf_reg &= ~0x03; + _conf_reg &= ~0x03; } - // ::printf("set_excitement enable=%d regA=0x%x\n", (int)enable, (unsigned)conf_reg); + // ::printf("set_excitement enable=%d regA=0x%x\n", (int)enable, (unsigned)_conf_reg); - ret = write_reg(ADDR_CONF_A, conf_reg); + ret = write_reg(ADDR_CONF_A, _conf_reg); if (OK != ret) perf_count(_comms_errors); @@ -1196,7 +1283,7 @@ int HMC5883::set_excitement(unsigned enable) //print_info(); - return !(conf_reg == conf_reg_ret); + return !(_conf_reg == conf_reg_ret); } int @@ -1257,12 +1344,12 @@ const int ERROR = -1; HMC5883 *g_dev_int; HMC5883 *g_dev_ext; -void hmc5883_usage(); void start(int bus, enum Rotation rotation); void test(int bus); void reset(int bus); void info(int bus); int calibrate(int bus); +void usage(); /** * Start the driver. @@ -1511,10 +1598,8 @@ info(int bus) exit(0); } -} // namespace - void -hmc5883_usage() +usage() { warnx("missing command: try 'start', 'info', 'test', 'reset', 'info', 'calibrate'"); warnx("options:"); @@ -1526,6 +1611,8 @@ hmc5883_usage() #endif } +} // namespace + int hmc5883_main(int argc, char *argv[]) { @@ -1551,7 +1638,7 @@ hmc5883_main(int argc, char *argv[]) calibrate = true; break; default: - hmc5883_usage(); + hmc5883::usage(); exit(0); } } -- cgit v1.2.3 From 67e3a904b6526f9268530d9c8e9529585c0be235 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:05:13 +0200 Subject: fix ms5611 code style for usage call --- src/drivers/ms5611/ms5611.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/drivers/ms5611/ms5611.cpp b/src/drivers/ms5611/ms5611.cpp index 7a8d2eecf..fe669b5f5 100644 --- a/src/drivers/ms5611/ms5611.cpp +++ b/src/drivers/ms5611/ms5611.cpp @@ -781,6 +781,7 @@ void test(); void reset(); void info(); void calibrate(unsigned altitude); +void usage(); /** * MS5611 crc4 cribbed from the datasheet @@ -1057,16 +1058,16 @@ calibrate(unsigned altitude) exit(0); } -} // namespace - void -ms5611_usage() +usage() { warnx("missing command: try 'start', 'info', 'test', 'test2', 'reset', 'calibrate'"); warnx("options:"); warnx(" -X (external bus)"); } +} // namespace + int ms5611_main(int argc, char *argv[]) { @@ -1080,7 +1081,7 @@ ms5611_main(int argc, char *argv[]) external_bus = true; break; default: - ms5611_usage(); + ms5611::usage(); exit(0); } } -- cgit v1.2.3 From 0d1ac4235411e8f05f96bcbe51558d92f0d86cf6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:10:08 +0200 Subject: airspeed calibration: Update and resolve compile errors --- src/modules/commander/airspeed_calibration.cpp | 75 ++++++++++++-------------- 1 file changed, 33 insertions(+), 42 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index a1a20abc9..421e53ae0 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -51,6 +51,7 @@ #include #include #include +#include /* oddly, ERROR is not defined for c++ */ #ifdef ERROR @@ -103,58 +104,48 @@ int do_airspeed_calibration(int mavlink_fd) } } - for (unsigned i = 0; i < (sizeof(diff_pres_offset) / sizeof(diff_pres_offset[0])); i++) { + unsigned calibration_counter = 0; - unsigned calibration_counter = 0; - - if (i == 0) { - mavlink_log_critical(mavlink_fd, "Ensure sensor is not measuring wind"); - usleep(500 * 1000); - } - - float diff_pres_offset = 0.0f; - - while (calibration_counter < calibration_count) { - - /* wait blocking for new data */ - struct pollfd fds[1]; - fds[0].fd = diff_pres_sub; - fds[0].events = POLLIN; - - int poll_ret = poll(fds, 1, 1000); - - if (poll_ret) { - orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); + mavlink_log_critical(mavlink_fd, "Ensure sensor is not measuring wind"); + usleep(500 * 1000); - if (i > 0) { + while (calibration_counter < calibration_count) { - if (calc_indicated_airspeed(fabsf(diff_pres.differential_pressure_raw_pa)) < 10.0f) { - mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot"); - usleep(5000 * 1000); - continue; - } + /* wait blocking for new data */ + struct pollfd fds[1]; + fds[0].fd = diff_pres_sub; + fds[0].events = POLLIN; - /* do not log negative values in the second go */ - if ((diff_pres_offset / calibration_counter) < calc_indicated_airspeed(-5.0f)) { - mavlink_log_critical(mavlink_fd, "Negative val: swap static<->dynamic ports,restart"); - close(diff_pres_sub); - return ERROR; - } - } + int poll_ret = poll(fds, 1, 1000); - diff_pres_offset += diff_pres.differential_pressure_raw_pa; - calibration_counter++; + if (poll_ret) { + orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); - if (calibration_counter % (calibration_count / 20) == 0) { - mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count / 2); - } + if (calc_indicated_airspeed(fabsf(diff_pres.differential_pressure_raw_pa)) < 10.0f) { + mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot"); + usleep(5000 * 1000); + continue; + } - } else if (poll_ret == 0) { - /* any poll failure for 1s is a reason to abort */ - mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); + /* do not log negative values in the second go */ + if ((diff_pres_offset / calibration_counter) < calc_indicated_airspeed(-5.0f)) { + mavlink_log_critical(mavlink_fd, "Negative val: swap static<->dynamic ports,restart"); close(diff_pres_sub); return ERROR; } + + diff_pres_offset += diff_pres.differential_pressure_raw_pa; + calibration_counter++; + + if (calibration_counter % (calibration_count / 20) == 0) { + mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count / 2); + } + + } else if (poll_ret == 0) { + /* any poll failure for 1s is a reason to abort */ + mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); + close(diff_pres_sub); + return ERROR; } } -- cgit v1.2.3 From e6b5e3ae613e89189ac69cf0b174b10002d51068 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:22:36 +0200 Subject: Add note about need to scan external buses first --- ROMFS/px4fmu_common/init.d/rc.sensors | 1 + 1 file changed, 1 insertion(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 1e14930fe..be54ea98b 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -24,6 +24,7 @@ fi if ver hwcmp PX4FMU_V2 then + # IMPORTANT: EXTERNAL BUSES SHOULD BE SCANNED FIRST if lsm303d start then echo "[init] Using LSM303D" -- cgit v1.2.3 From 8960c9e0a8b165ce15cf1864d61f8f764935a081 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:28:10 +0200 Subject: better submodule instructions --- Tools/check_submodules.sh | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index cc6e7d1c0..8adc6b6c7 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -12,8 +12,12 @@ if [ -d NuttX/nuttx ]; if [ -z "$STATUSRETVAL" ]; then echo "Checked NuttX submodule, correct version found" else - echo "NuttX sub repo not at correct version. Try 'git submodule update'" - echo "or follow instructions on http://pixhawk.org/dev/git/submodules" + echo "" + echo "" + echo " NuttX sub repo not at correct version. Try 'git submodule update'" + echo " or follow instructions on http://pixhawk.org/dev/git/submodules" + echo "" + echo " DO NOT FORGET TO RUN 'make distclean && make archives' AFTER EACH NUTTX UPDATE!" echo "" echo "" echo "New commits required:" @@ -33,6 +37,8 @@ if [ -d mavlink/include/mavlink/v1.0 ]; if [ -z "$STATUSRETVAL" ]; then echo "Checked mavlink submodule, correct version found" else + echo "" + echo "" echo "mavlink sub repo not at correct version. Try 'git submodule update'" echo "or follow instructions on http://pixhawk.org/dev/git/submodules" echo "" -- cgit v1.2.3 From d6632ee2dda39de78be1bbfa6754af8b59c58655 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:34:06 +0200 Subject: ardrone: Optimize for size, since performance is good at any rate --- src/drivers/ardrone_interface/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/ardrone_interface/module.mk b/src/drivers/ardrone_interface/module.mk index d8e6c76c6..285db1351 100644 --- a/src/drivers/ardrone_interface/module.mk +++ b/src/drivers/ardrone_interface/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = ardrone_interface SRCS = ardrone_interface.c \ ardrone_motor_control.c MODULE_STACKSIZE = 1200 + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 85301e1172a0ab7cf726ba8ffc5386ab7ede363d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:34:28 +0200 Subject: frsky: Optimize for size --- src/drivers/frsky_telemetry/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/frsky_telemetry/module.mk b/src/drivers/frsky_telemetry/module.mk index 9a49589ee..78ad6f67e 100644 --- a/src/drivers/frsky_telemetry/module.mk +++ b/src/drivers/frsky_telemetry/module.mk @@ -41,3 +41,5 @@ SRCS = frsky_data.c \ frsky_telemetry.c MODULE_STACKSIZE = 1200 + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 144bb89e027701f0b4c1661685d770a013c100f6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:34:40 +0200 Subject: HoTT: optimize for size --- src/drivers/hott/hott_sensors/module.mk | 2 ++ src/drivers/hott/hott_telemetry/module.mk | 2 ++ 2 files changed, 4 insertions(+) diff --git a/src/drivers/hott/hott_sensors/module.mk b/src/drivers/hott/hott_sensors/module.mk index b5f5762ba..47aea6caf 100644 --- a/src/drivers/hott/hott_sensors/module.mk +++ b/src/drivers/hott/hott_sensors/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = hott_sensors SRCS = hott_sensors.cpp \ ../messages.cpp \ ../comms.cpp + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/hott/hott_telemetry/module.mk b/src/drivers/hott/hott_telemetry/module.mk index b19cbd14c..cd7bdbc85 100644 --- a/src/drivers/hott/hott_telemetry/module.mk +++ b/src/drivers/hott/hott_telemetry/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = hott_telemetry SRCS = hott_telemetry.cpp \ ../messages.cpp \ ../comms.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From aaf2652e26106b0850226f25cd12ce1304775522 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:34:58 +0200 Subject: MKBLCTRL: optimize for size --- src/drivers/mkblctrl/module.mk | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/drivers/mkblctrl/module.mk b/src/drivers/mkblctrl/module.mk index 3ac263b00..6daa14aa5 100644 --- a/src/drivers/mkblctrl/module.mk +++ b/src/drivers/mkblctrl/module.mk @@ -37,6 +37,8 @@ MODULE_COMMAND = mkblctrl -SRCS = mkblctrl.cpp +SRCS = mkblctrl.cpp INCLUDE_DIRS += $(TOPDIR)/arch/arm/src/stm32 $(TOPDIR)/arch/arm/src/common + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 70d0ff492220371c57f9ee3d1f4fedb2fcf1199f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:35:11 +0200 Subject: SF0X: optimize for size --- src/drivers/sf0x/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/sf0x/module.mk b/src/drivers/sf0x/module.mk index dc93a90e7..dc2c66d56 100644 --- a/src/drivers/sf0x/module.mk +++ b/src/drivers/sf0x/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = sf0x SRCS = sf0x.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 959bf6a2c8ac656b1536762a2a7aea0c5349f5d5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 19:35:49 +0200 Subject: ll40ls: Optimize for size --- src/drivers/ll40ls/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/ll40ls/module.mk b/src/drivers/ll40ls/module.mk index ab7d43269..fb627afee 100644 --- a/src/drivers/ll40ls/module.mk +++ b/src/drivers/ll40ls/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = ll40ls SRCS = ll40ls.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 8a6e69ed671d3de6b267518f1cd425b24e48c71e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 20:08:36 +0200 Subject: Fix up RAM usage of fixed wing apps --- src/modules/fw_att_control/module.mk | 2 ++ src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 2 +- src/modules/fw_pos_control_l1/module.mk | 4 +++- 3 files changed, 6 insertions(+), 2 deletions(-) diff --git a/src/modules/fw_att_control/module.mk b/src/modules/fw_att_control/module.mk index 1e600757e..89c6494c5 100644 --- a/src/modules/fw_att_control/module.mk +++ b/src/modules/fw_att_control/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = fw_att_control SRCS = fw_att_control_main.cpp \ fw_att_control_params.c + +MODULE_STACKSIZE = 1200 diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 3d6c62434..98ccd09a5 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -1445,7 +1445,7 @@ FixedwingPositionControl::start() _control_task = task_spawn_cmd("fw_pos_control_l1", SCHED_DEFAULT, SCHED_PRIORITY_MAX - 5, - 3500, + 2000, (main_t)&FixedwingPositionControl::task_main_trampoline, nullptr); diff --git a/src/modules/fw_pos_control_l1/module.mk b/src/modules/fw_pos_control_l1/module.mk index af155fe08..15b575b50 100644 --- a/src/modules/fw_pos_control_l1/module.mk +++ b/src/modules/fw_pos_control_l1/module.mk @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2013 PX4 Development Team. All rights reserved. +# Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. # # Redistribution and use in source and binary forms, with or without # modification, are permitted provided that the following conditions @@ -43,3 +43,5 @@ SRCS = fw_pos_control_l1_main.cpp \ mtecs/mTecs.cpp \ mtecs/limitoverride.cpp \ mtecs/mTecs_params.c + +MODULE_STACKSIZE = 1200 -- cgit v1.2.3 From f32a51f51597bb66c7e404a7dc8e723c32f44743 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 20:14:01 +0200 Subject: Fixed battery ignore voltage to a higher value --- src/modules/sensors/sensors.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 6e2d906e6..c40e52a0d 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -133,7 +133,7 @@ #endif #define BATT_V_LOWPASS 0.001f -#define BATT_V_IGNORE_THRESHOLD 3.5f +#define BATT_V_IGNORE_THRESHOLD 4.8f /** * HACK - true temperature is much less than indicated temperature in baro, -- cgit v1.2.3 From c059fb03ea5ba85446d93df4db73e867f01e288d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 21:33:09 +0200 Subject: blinkm: Make driver flash efficient --- src/drivers/blinkm/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/blinkm/module.mk b/src/drivers/blinkm/module.mk index b48b90f3f..c90673317 100644 --- a/src/drivers/blinkm/module.mk +++ b/src/drivers/blinkm/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = blinkm SRCS = blinkm.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 69937702b8ff4ee052e960f6427e4653b4743e2a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 21:33:21 +0200 Subject: gps: Flash efficiency --- src/drivers/gps/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/gps/module.mk b/src/drivers/gps/module.mk index eb382c4b2..b00818424 100644 --- a/src/drivers/gps/module.mk +++ b/src/drivers/gps/module.mk @@ -43,3 +43,5 @@ SRCS = gps.cpp \ ubx.cpp MODULE_STACKSIZE = 1200 + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 5f8baed876a805c2cfae7c0ed0250ae20b501336 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 21:33:34 +0200 Subject: mb12xx: flash efficiency --- src/drivers/mb12xx/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/mb12xx/module.mk b/src/drivers/mb12xx/module.mk index 4e00ada02..d751e93e4 100644 --- a/src/drivers/mb12xx/module.mk +++ b/src/drivers/mb12xx/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = mb12xx SRCS = mb12xx.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 7bf0e6f3e26ee9e10073293677563f6862758557 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 21:47:26 +0200 Subject: Better airspeed feedback --- src/modules/commander/airspeed_calibration.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 421e53ae0..a1b8816ff 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -200,13 +200,13 @@ int do_airspeed_calibration(int mavlink_fd) float curr_avg = (diff_pres_offset / calibration_counter); if (calc_indicated_airspeed(fabsf(curr_avg)) < 10.0f) { - mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot"); + mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot (%.1f m/s)", curr_avg); usleep(5000 * 1000); continue; } /* do not log negative values in the second go */ - if (curr_avg < calc_indicated_airspeed(-5.0f)) { + if (curr_avg < -calc_indicated_airspeed(5.0f)) { mavlink_log_critical(mavlink_fd, "Negative val: swap static<->dynamic ports,restart"); close(diff_pres_sub); -- cgit v1.2.3 From 67d23253c3b3ec04bfd9d5f7e09d3d405ceba7c6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 22:00:50 +0200 Subject: airspeed cal build fix --- src/modules/commander/airspeed_calibration.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index a1b8816ff..529a5b32f 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -200,7 +200,7 @@ int do_airspeed_calibration(int mavlink_fd) float curr_avg = (diff_pres_offset / calibration_counter); if (calc_indicated_airspeed(fabsf(curr_avg)) < 10.0f) { - mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot (%.1f m/s)", curr_avg); + mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot (%.1f m/s)", (double)curr_avg); usleep(5000 * 1000); continue; } -- cgit v1.2.3 From fe5d35bc546232b2d897e7509c28441178b6e7ea Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 22:04:04 +0200 Subject: Reduce IO buf space reasonably --- nuttx-configs/px4fmu-v1/nsh/defconfig | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/nuttx-configs/px4fmu-v1/nsh/defconfig b/nuttx-configs/px4fmu-v1/nsh/defconfig index 6717ae19a..a651faffa 100644 --- a/nuttx-configs/px4fmu-v1/nsh/defconfig +++ b/nuttx-configs/px4fmu-v1/nsh/defconfig @@ -679,7 +679,7 @@ CONFIG_BUILTIN=y # # Standard C Library Options # -CONFIG_STDIO_BUFFER_SIZE=256 +CONFIG_STDIO_BUFFER_SIZE=180 CONFIG_STDIO_LINEBUFFER=y CONFIG_NUNGET_CHARS=2 CONFIG_LIB_HOMEDIR="/" -- cgit v1.2.3 From 4824a4e8ac93d992e1401f768291cca65ba46acc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 22:18:59 +0200 Subject: Fix for dynamic / static part of calibration --- src/modules/commander/airspeed_calibration.cpp | 19 +++---------------- 1 file changed, 3 insertions(+), 16 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 529a5b32f..01db34be2 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -121,19 +121,6 @@ int do_airspeed_calibration(int mavlink_fd) if (poll_ret) { orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); - if (calc_indicated_airspeed(fabsf(diff_pres.differential_pressure_raw_pa)) < 10.0f) { - mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot"); - usleep(5000 * 1000); - continue; - } - - /* do not log negative values in the second go */ - if ((diff_pres_offset / calibration_counter) < calc_indicated_airspeed(-5.0f)) { - mavlink_log_critical(mavlink_fd, "Negative val: swap static<->dynamic ports,restart"); - close(diff_pres_sub); - return ERROR; - } - diff_pres_offset += diff_pres.differential_pressure_raw_pa; calibration_counter++; @@ -197,16 +184,16 @@ int do_airspeed_calibration(int mavlink_fd) diff_pres_offset += diff_pres.differential_pressure_raw_pa; calibration_counter++; - float curr_avg = (diff_pres_offset / calibration_counter); + float curr_avg_airspeed = calc_indicated_airspeed(diff_pres_offset / calibration_counter); - if (calc_indicated_airspeed(fabsf(curr_avg)) < 10.0f) { + if (fabsf(curr_avg) < 10.0f) { mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot (%.1f m/s)", (double)curr_avg); usleep(5000 * 1000); continue; } /* do not log negative values in the second go */ - if (curr_avg < -calc_indicated_airspeed(5.0f)) { + if (curr_avg_airspeed < -calc_indicated_airspeed(5.0f)) { mavlink_log_critical(mavlink_fd, "Negative val: swap static<->dynamic ports,restart"); close(diff_pres_sub); -- cgit v1.2.3 From 34abf5c40cda538f204d313cc49715b5a938d168 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 22:50:56 +0200 Subject: airspeed cal: Fix up logic --- src/modules/commander/airspeed_calibration.cpp | 25 +++++++++++-------------- 1 file changed, 11 insertions(+), 14 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 01db34be2..47c9c7af5 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -165,11 +165,8 @@ int do_airspeed_calibration(int mavlink_fd) /* wait 500 ms to ensure parameter propagated through the system */ usleep(500 * 1000); - calibration_counter = 0; - diff_pres_offset = 0.0f; - /* just take a few samples and make sure pitot tubes are not reversed */ - while (calibration_counter < 50) { + while (calibration_counter < 10) { /* wait blocking for new data */ struct pollfd fds[1]; @@ -181,19 +178,15 @@ int do_airspeed_calibration(int mavlink_fd) if (poll_ret) { orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); - diff_pres_offset += diff_pres.differential_pressure_raw_pa; - calibration_counter++; - - float curr_avg_airspeed = calc_indicated_airspeed(diff_pres_offset / calibration_counter); - - if (fabsf(curr_avg) < 10.0f) { - mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot (%.1f m/s)", (double)curr_avg); - usleep(5000 * 1000); + if (fabsf(diff_pres.differential_pressure_raw_pa) < 10.0f) { + mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot (%.1f Pa)", + (double)diff_pres.differential_pressure_raw_pa); + usleep(3000 * 1000); continue; } - /* do not log negative values in the second go */ - if (curr_avg_airspeed < -calc_indicated_airspeed(5.0f)) { + /* do not allow negative values */ + if (diff_pres.differential_pressure_raw_pa < 0.0f) { mavlink_log_critical(mavlink_fd, "Negative val: swap static<->dynamic ports,restart"); close(diff_pres_sub); @@ -209,7 +202,11 @@ int do_airspeed_calibration(int mavlink_fd) /* save */ (void)param_save_default(); + close(diff_pres_sub); return ERROR; + } else { + close(diff_pres_sub); + return OK; } } else if (poll_ret == 0) { -- cgit v1.2.3 From 65409ad2c8ba10d95cbcfa088951abc40eb46774 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 23:30:00 +0200 Subject: Airspeed calibration improvements --- src/modules/commander/airspeed_calibration.cpp | 23 +++++++++++++++-------- 1 file changed, 15 insertions(+), 8 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 47c9c7af5..d52cafb8f 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -125,7 +125,7 @@ int do_airspeed_calibration(int mavlink_fd) calibration_counter++; if (calibration_counter % (calibration_count / 20) == 0) { - mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count / 2); + mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 80) / calibration_count); } } else if (poll_ret == 0) { @@ -165,6 +165,8 @@ int do_airspeed_calibration(int mavlink_fd) /* wait 500 ms to ensure parameter propagated through the system */ usleep(500 * 1000); + calibration_counter = 0; + /* just take a few samples and make sure pitot tubes are not reversed */ while (calibration_counter < 10) { @@ -178,16 +180,18 @@ int do_airspeed_calibration(int mavlink_fd) if (poll_ret) { orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); - if (fabsf(diff_pres.differential_pressure_raw_pa) < 10.0f) { - mavlink_log_critical(mavlink_fd, "Put a finger on front hole of pitot (%.1f Pa)", - (double)diff_pres.differential_pressure_raw_pa); + float calibrated_pa = diff_pres.differential_pressure_raw_pa - diff_pres_offset; + + if (fabsf(calibrated_pa) < 9.0f) { + mavlink_log_critical(mavlink_fd, "Create airflow on pitot (%.1f Pa, #h101)", + (double)calibrated_pa); usleep(3000 * 1000); continue; } /* do not allow negative values */ - if (diff_pres.differential_pressure_raw_pa < 0.0f) { - mavlink_log_critical(mavlink_fd, "Negative val: swap static<->dynamic ports,restart"); + if (calibrated_pa < 0.0f) { + mavlink_log_critical(mavlink_fd, "Negative val: swap static vs dynamic ports,restart"); close(diff_pres_sub); /* the user setup is wrong, wipe the calibration to force a proper re-calibration */ @@ -205,8 +209,9 @@ int do_airspeed_calibration(int mavlink_fd) close(diff_pres_sub); return ERROR; } else { - close(diff_pres_sub); - return OK; + mavlink_log_info(mavlink_fd, "positive pressure: (%.1f Pa)", + (double)diff_pres.differential_pressure_raw_pa); + break; } } else if (poll_ret == 0) { @@ -217,6 +222,8 @@ int do_airspeed_calibration(int mavlink_fd) } } + mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 100); + mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name); tune_neutral(true); close(diff_pres_sub); -- cgit v1.2.3 From cdfbe9bcc41a6e8e8b2a6f95bd69283ee5176966 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 12 Jul 2014 23:30:34 +0200 Subject: px4io: Do not forward excessively low battery voltages --- src/drivers/px4io/px4io.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 24da4c68b..7d78b0d27 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1383,7 +1383,7 @@ void PX4IO::io_handle_battery(uint16_t vbatt, uint16_t ibatt) { /* only publish if battery has a valid minimum voltage */ - if (vbatt <= 3300) { + if (vbatt <= 4900) { return; } -- cgit v1.2.3 From 1b6ad3e1990bec84489f949b195adba4412e1c7d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:37:10 +0200 Subject: ekf: Logic cleanup and print code cleanup --- .../ekf_att_pos_estimator_main.cpp | 137 ++++++++------------- 1 file changed, 49 insertions(+), 88 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index bc5f709e5..5ce6bdb0a 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -559,61 +559,26 @@ FixedwingEstimator::check_filter_state() int check = _ekf->CheckAndBound(&ekf_report); - const char* ekfname = "att pos estimator: "; - - switch (check) { - case 0: - /* all ok */ - break; - case 1: - { - const char* str = "NaN in states, resetting"; - warnx("%s", str); - mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str); - break; - } - case 2: - { - const char* str = "stale IMU data, resetting"; - warnx("%s", str); - mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str); - break; - } - case 3: - { - const char* str = "switching to dynamic state"; - warnx("%s", str); - mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str); - break; - } - case 4: - { - const char* str = "excessive gyro offsets"; - warnx("%s", str); - mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str); - break; - } - case 5: - { - const char* str = "GPS velocity divergence"; - warnx("%s", str); - mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str); - break; - } - case 6: - { - const char* str = "excessive covariances"; - warnx("%s", str); - mavlink_log_info(_mavlink_fd, "%s%s", ekfname, str); - break; + const char* const feedback[] = { 0, + "NaN in states, resetting", + "stale IMU data, resetting", + "got initial position lock", + "excessive gyro offsets", + "GPS velocity divergence", + "excessive covariances", + "unknown condition"}; + + // Print out error condition + if (check) { + unsigned warn_index = static_cast(check); + unsigned max_warn_index = (sizeof(feedback) / sizeof(feedback[0])); + + if (max_warn_index < warn_index) { + warn_index = max_warn_index; } - default: - { - const char* str = "unknown reset condition"; - warnx("%s", str); - mavlink_log_critical(_mavlink_fd, "%s%s", ekfname, str); - } + warnx("reset: %s", feedback[warn_index]); + mavlink_log_critical(_mavlink_fd, "[ekf] re-init: %s", feedback[warn_index]); } struct estimator_status_report rep; @@ -1140,20 +1105,6 @@ FixedwingEstimator::task_main() float initVelNED[3]; - // Guard before running any parts of the filter - // of NaN / invalid values - if (_ekf->statesInitialised) { - - // We're apparently initialized in this case now - - int check = check_filter_state(); - - if (check) { - // Let the system re-initialize itself - continue; - } - } - /* Initialize the filter first */ if (!_gps_initialized && _gps.fix_type > 2 && _gps.eph < _parameters.pos_stddev_threshold && _gps.epv < _parameters.pos_stddev_threshold) { @@ -1216,8 +1167,17 @@ FixedwingEstimator::task_main() _baro_gps_offset = 0.0f; _ekf->InitialiseFilter(initVelNED, 0.0, 0.0, 0.0f, 0.0f); + } else if (_ekf->statesInitialised) { + // We're apparently initialized in this case now + int check = check_filter_state(); + + if (check) { + // Let the system re-initialize itself + continue; + } + // Run the strapdown INS equations every IMU update _ekf->UpdateStrapdownEquationsNED(); #if 0 @@ -1285,7 +1245,7 @@ FixedwingEstimator::task_main() // run the fusion step _ekf->FuseVelposNED(); - } else if (!_gps_initialized && _ekf->statesInitialised) { + } else if (!_gps_initialized) { // Convert GPS measurements to Pos NE, hgt and Vel NED _ekf->velNED[0] = 0.0f; _ekf->velNED[1] = 0.0f; @@ -1307,7 +1267,7 @@ FixedwingEstimator::task_main() _ekf->fusePosData = false; } - if (newHgtData && _ekf->statesInitialised) { + if (newHgtData) { // Could use a blend of GPS and baro alt data if desired _ekf->hgtMea = 1.0f * (_ekf->baroHgt - _baro_ref); _ekf->fuseHgtData = true; @@ -1321,7 +1281,7 @@ FixedwingEstimator::task_main() } // Fuse Magnetometer Measurements - if (newDataMag && _ekf->statesInitialised) { + if (newDataMag) { _ekf->fuseMagData = true; _ekf->RecallStates(_ekf->statesAtMagMeasTime, (IMUmsec - _parameters.mag_delay_ms)); // Assume 50 msec avg delay for magnetometer data @@ -1335,7 +1295,7 @@ FixedwingEstimator::task_main() } // Fuse Airspeed Measurements - if (newAdsData && _ekf->statesInitialised && _ekf->VtasMeas > 8.0f) { + if (newAdsData && _ekf->VtasMeas > 7.0f) { _ekf->fuseVtasData = true; _ekf->RecallStates(_ekf->statesAtVtasMeasTime, (IMUmsec - _parameters.tas_delay_ms)); // assume 100 msec avg delay for airspeed data _ekf->FuseAirspeed(); @@ -1403,7 +1363,7 @@ FixedwingEstimator::task_main() _velocity_xy_filtered = 0.95f*_velocity_xy_filtered + 0.05f*sqrtf(_local_pos.vx*_local_pos.vx + _local_pos.vy*_local_pos.vy); _velocity_z_filtered = 0.95f*_velocity_z_filtered + 0.05f*fabsf(_local_pos.vz); - _airspeed_filtered = 0.95f*_airspeed_filtered + + 0.05f*_airspeed.true_airspeed_m_s; + _airspeed_filtered = 0.95f*_airspeed_filtered + 0.05f*_airspeed.true_airspeed_m_s; /* crude land detector for fixedwing only, @@ -1494,27 +1454,28 @@ FixedwingEstimator::task_main() } - } - - } + if (hrt_elapsed_time(&_wind.timestamp) > 99000) { + _wind.timestamp = _global_pos.timestamp; + _wind.windspeed_north = _ekf->states[14]; + _wind.windspeed_east = _ekf->states[15]; + _wind.covariance_north = _ekf->P[14][14]; + _wind.covariance_east = _ekf->P[15][15]; - if (hrt_elapsed_time(&_wind.timestamp) > 99000) { - _wind.timestamp = _global_pos.timestamp; - _wind.windspeed_north = _ekf->states[14]; - _wind.windspeed_east = _ekf->states[15]; - _wind.covariance_north = _ekf->P[14][14]; - _wind.covariance_east = _ekf->P[15][15]; + /* lazily publish the wind estimate only once available */ + if (_wind_pub > 0) { + /* publish the wind estimate */ + orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind); - /* lazily publish the wind estimate only once available */ - if (_wind_pub > 0) { - /* publish the wind estimate */ - orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind); + } else { + /* advertise and publish */ + _wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind); + } + } - } else { - /* advertise and publish */ - _wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind); } + } + } } -- cgit v1.2.3 From be5ac5e4127d09187ef0e19a7955cca9b0f1b378 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:38:52 +0200 Subject: Fix mavlink log header docs. --- src/include/mavlink/mavlink_log.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/include/mavlink/mavlink_log.h b/src/include/mavlink/mavlink_log.h index 0ea655cac..6d56c546a 100644 --- a/src/include/mavlink/mavlink_log.h +++ b/src/include/mavlink/mavlink_log.h @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved. - * Author: Lorenz Meier + * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions -- cgit v1.2.3 From 716e20fab6d63f3dc6f80c70f382d6b0f45f9340 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:39:13 +0200 Subject: Fix accel cal docs. --- src/modules/commander/accelerometer_calibration.cpp | 3 +-- src/modules/commander/accelerometer_calibration.h | 3 +-- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp index be465ab76..7a4e7a766 100644 --- a/src/modules/commander/accelerometer_calibration.cpp +++ b/src/modules/commander/accelerometer_calibration.cpp @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. - * Author: Anton Babushkin + * Copyright (c) 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/src/modules/commander/accelerometer_calibration.h b/src/modules/commander/accelerometer_calibration.h index 1cf9c0977..6b7e16d44 100644 --- a/src/modules/commander/accelerometer_calibration.h +++ b/src/modules/commander/accelerometer_calibration.h @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. - * Author: Anton Babushkin + * Copyright (c) 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions -- cgit v1.2.3 From 259014b0d50426b0fbed3b9eac5a1d34aaa5b211 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:40:09 +0200 Subject: Documentation only and unused defines only cleanup. --- src/modules/commander/airspeed_calibration.h | 2 +- src/modules/commander/baro_calibration.cpp | 2 +- src/modules/commander/baro_calibration.h | 2 +- src/modules/commander/calibration_messages.h | 3 +-- src/modules/commander/calibration_routines.cpp | 3 +-- src/modules/commander/calibration_routines.h | 3 +-- src/modules/commander/mag_calibration.h | 2 +- src/modules/commander/state_machine_helper.h | 10 ++++------ 8 files changed, 11 insertions(+), 16 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.h b/src/modules/commander/airspeed_calibration.h index 71c701fc2..8c6b65ff1 100644 --- a/src/modules/commander/airspeed_calibration.h +++ b/src/modules/commander/airspeed_calibration.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/src/modules/commander/baro_calibration.cpp b/src/modules/commander/baro_calibration.cpp index 3123c4087..da98644b4 100644 --- a/src/modules/commander/baro_calibration.cpp +++ b/src/modules/commander/baro_calibration.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/src/modules/commander/baro_calibration.h b/src/modules/commander/baro_calibration.h index bc42bc6cf..ce78ae700 100644 --- a/src/modules/commander/baro_calibration.h +++ b/src/modules/commander/baro_calibration.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/src/modules/commander/calibration_messages.h b/src/modules/commander/calibration_messages.h index fd8b8564d..b1e209efc 100644 --- a/src/modules/commander/calibration_messages.h +++ b/src/modules/commander/calibration_messages.h @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. - * Author: Anton Babushkin + * Copyright (c) 2013 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/src/modules/commander/calibration_routines.cpp b/src/modules/commander/calibration_routines.cpp index 43f341ae7..5796204bf 100644 --- a/src/modules/commander/calibration_routines.cpp +++ b/src/modules/commander/calibration_routines.cpp @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: Lorenz Meier + * Copyright (c) 2012 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/src/modules/commander/calibration_routines.h b/src/modules/commander/calibration_routines.h index e3e7fbafd..3c8e49ee9 100644 --- a/src/modules/commander/calibration_routines.h +++ b/src/modules/commander/calibration_routines.h @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2012 PX4 Development Team. All rights reserved. - * Author: Lorenz Meier + * Copyright (c) 2012 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/src/modules/commander/mag_calibration.h b/src/modules/commander/mag_calibration.h index a101cd7b1..c14f948cc 100644 --- a/src/modules/commander/mag_calibration.h +++ b/src/modules/commander/mag_calibration.h @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h index ddc5bf154..bb1b87e71 100644 --- a/src/modules/commander/state_machine_helper.h +++ b/src/modules/commander/state_machine_helper.h @@ -1,8 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. - * Author: Thomas Gubler - * Julian Oes + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -36,14 +34,14 @@ /** * @file state_machine_helper.h * State machine helper functions definitions + * + * @author Thomas Gubler + * @author Julian Oes */ #ifndef STATE_MACHINE_HELPER_H_ #define STATE_MACHINE_HELPER_H_ -#define GPS_NOFIX_COUNTER_LIMIT 4 //need GPS_NOFIX_COUNTER_LIMIT gps packets with a bad fix to call an error (if outdoor) -#define GPS_GOTFIX_COUNTER_REQUIRED 4 //need GPS_GOTFIX_COUNTER_REQUIRED gps packets with a good fix to obtain position lock - #include #include #include -- cgit v1.2.3 From ea11bc6c4bf7180ae4e321eebcaf817eebb18e6c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:41:39 +0200 Subject: Command handling: Fix up local variable usage and status prints. --- src/modules/commander/commander.cpp | 67 +++++++++++++++++++++---------------- 1 file changed, 38 insertions(+), 29 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index e14dff197..009e0ac01 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -403,10 +403,12 @@ transition_result_t arm_disarm(bool arm, const int mavlink_fd_local, const char return arming_res; } -bool handle_command(struct vehicle_status_s *status, const struct safety_s *safety, struct vehicle_command_s *cmd, struct actuator_armed_s *armed, struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub) +bool handle_command(struct vehicle_status_s *status_local, const struct safety_s *safety_local, + struct vehicle_command_s *cmd, struct actuator_armed_s *armed_local, + struct home_position_s *home, struct vehicle_global_position_s *global_pos, orb_advert_t *home_pub) { /* only handle commands that are meant to be handled by this system and component */ - if (cmd->target_system != status->system_id || ((cmd->target_component != status->component_id) && (cmd->target_component != 0))) { // component_id 0: valid for all components + if (cmd->target_system != status_local->system_id || ((cmd->target_component != status_local->component_id) && (cmd->target_component != 0))) { // component_id 0: valid for all components return false; } @@ -425,7 +427,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe /* set HIL state */ hil_state_t new_hil_state = (base_mode & MAV_MODE_FLAG_HIL_ENABLED) ? HIL_STATE_ON : HIL_STATE_OFF; - transition_result_t hil_ret = hil_state_transition(new_hil_state, status_pub, status, mavlink_fd); + transition_result_t hil_ret = hil_state_transition(new_hil_state, status_pub, status_local, mavlink_fd); // Transition the arming state arming_ret = arm_disarm(base_mode & MAV_MODE_FLAG_SAFETY_ARMED, mavlink_fd, "set mode command"); @@ -434,43 +436,43 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe /* use autopilot-specific mode */ if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_MANUAL) { /* MANUAL */ - main_ret = main_state_transition(status, MAIN_STATE_MANUAL); + main_ret = main_state_transition(status_local, MAIN_STATE_MANUAL); } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ALTCTL) { /* ALTCTL */ - main_ret = main_state_transition(status, MAIN_STATE_ALTCTL); + main_ret = main_state_transition(status_local, MAIN_STATE_ALTCTL); } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_POSCTL) { /* POSCTL */ - main_ret = main_state_transition(status, MAIN_STATE_POSCTL); + main_ret = main_state_transition(status_local, MAIN_STATE_POSCTL); } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_AUTO) { /* AUTO */ - main_ret = main_state_transition(status, MAIN_STATE_AUTO_MISSION); + main_ret = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION); } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_ACRO) { /* ACRO */ - main_ret = main_state_transition(status, MAIN_STATE_ACRO); + main_ret = main_state_transition(status_local, MAIN_STATE_ACRO); } else if (custom_main_mode == PX4_CUSTOM_MAIN_MODE_OFFBOARD) { /* OFFBOARD */ - main_ret = main_state_transition(status, MAIN_STATE_OFFBOARD); + main_ret = main_state_transition(status_local, MAIN_STATE_OFFBOARD); } } else { /* use base mode */ if (base_mode & MAV_MODE_FLAG_AUTO_ENABLED) { /* AUTO */ - main_ret = main_state_transition(status, MAIN_STATE_AUTO_MISSION); + main_ret = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION); } else if (base_mode & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED) { if (base_mode & MAV_MODE_FLAG_GUIDED_ENABLED) { /* POSCTL */ - main_ret = main_state_transition(status, MAIN_STATE_POSCTL); + main_ret = main_state_transition(status_local, MAIN_STATE_POSCTL); } else if (base_mode & MAV_MODE_FLAG_STABILIZE_ENABLED) { /* MANUAL */ - main_ret = main_state_transition(status, MAIN_STATE_MANUAL); + main_ret = main_state_transition(status_local, MAIN_STATE_MANUAL); } } } @@ -485,22 +487,25 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe break; case VEHICLE_CMD_COMPONENT_ARM_DISARM: { - // Follow exactly what the mavlink spec says for values: 0.0f for disarm, 1.0f for arm. - // We use an float epsilon delta to test float equality. - if (cmd->param1 != 0.0f && (fabsf(cmd->param1 - 1.0f) > 2.0f * FLT_EPSILON)) { - mavlink_log_info(mavlink_fd, "Unsupported ARM_DISARM parameter: %.6f", (double)cmd->param1); + // Adhere to MAVLink specs, but base on knowledge that these fundamentally encode ints + // for logic state parameters + + if (static_cast(cmd->param1 + 0.5f) != 0 && static_cast(cmd->param1 + 0.5f) != 1) { + mavlink_log_critical(mavlink_fd, "Unsupported ARM_DISARM param: %.3f", (double)cmd->param1); } else { + bool cmd_arms = (static_cast(cmd->param1 + 0.5f) == 1); + // Flick to inair restore first if this comes from an onboard system - if (cmd->source_system == status->system_id && cmd->source_component == status->component_id) { - status->arming_state = ARMING_STATE_IN_AIR_RESTORE; + if (cmd->source_system == status_local->system_id && cmd->source_component == status_local->component_id) { + status_local->arming_state = ARMING_STATE_IN_AIR_RESTORE; } - transition_result_t arming_res = arm_disarm(cmd->param1 != 0.0f, mavlink_fd, "arm/disarm component command"); + transition_result_t arming_res = arm_disarm(cmd_arms, mavlink_fd, "arm/disarm component command"); if (arming_res == TRANSITION_DENIED) { - mavlink_log_critical(mavlink_fd, "#audio: REJECTING component arm cmd"); + mavlink_log_critical(mavlink_fd, "REJECTING component arm cmd"); cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED; } else { @@ -512,20 +517,24 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe case VEHICLE_CMD_OVERRIDE_GOTO: { // TODO listen vehicle_command topic directly from navigator (?) - unsigned int mav_goto = cmd->param1; + + // Increase by 0.5f and rely on the integer cast + // implicit floor(). This is the *safest* way to + // convert from floats representing small ints to actual ints. + unsigned int mav_goto = (cmd->param1 + 0.5f); if (mav_goto == 0) { // MAV_GOTO_DO_HOLD - status->nav_state = NAVIGATION_STATE_AUTO_LOITER; - mavlink_log_critical(mavlink_fd, "#audio: pause mission cmd"); + status_local->nav_state = NAVIGATION_STATE_AUTO_LOITER; + mavlink_log_critical(mavlink_fd, "Pause mission cmd"); cmd_result = VEHICLE_CMD_RESULT_ACCEPTED; } else if (mav_goto == 1) { // MAV_GOTO_DO_CONTINUE - status->nav_state = NAVIGATION_STATE_AUTO_MISSION; - mavlink_log_critical(mavlink_fd, "#audio: continue mission cmd"); + status_local->nav_state = NAVIGATION_STATE_AUTO_MISSION; + mavlink_log_critical(mavlink_fd, "Continue mission cmd"); cmd_result = VEHICLE_CMD_RESULT_ACCEPTED; } else { - mavlink_log_info(mavlink_fd, "Unsupported OVERRIDE_GOTO: %f %f %f %f %f %f %f %f", + mavlink_log_critical(mavlink_fd, "REJ CMD: %.1f %.1f %.1f %.1f %.1f %.1f %.1f %.1f", (double)cmd->param1, (double)cmd->param2, (double)cmd->param3, @@ -543,7 +552,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe //XXX: to enable the parachute, a param needs to be set //xxx: for safety only for now, param3 is unused by VEHICLE_CMD_DO_SET_SERVO - if (armed->armed && cmd->param3 > 0.5 && parachute_enabled) { + if (armed_local->armed && cmd->param3 > 0.5 && parachute_enabled) { transition_result_t failsafe_res = failsafe_state_transition(status, FAILSAFE_STATE_TERMINATION); cmd_result = VEHICLE_CMD_RESULT_ACCEPTED; @@ -561,7 +570,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe if (use_current) { /* use current position */ - if (status->condition_global_position_valid) { + if (status_local->condition_global_position_valid) { home->lat = global_pos->lat; home->lon = global_pos->lon; home->alt = global_pos->alt; @@ -598,7 +607,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe } /* mark home position as set */ - status->condition_home_position_valid = true; + status_local->condition_home_position_valid = true; } } break; -- cgit v1.2.3 From 3ec9ffa66166b10101887cc4077d1b02d4a0897b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:42:02 +0200 Subject: Buzzer and led: Fix -Wshadow warnings. --- src/modules/commander/commander.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 009e0ac01..85c9ccbaa 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -697,11 +697,11 @@ int commander_thread_main(int argc, char *argv[]) /* initialize */ if (led_init() != 0) { - warnx("ERROR: Failed to initialize leds"); + warnx("ERROR: LED INIT FAIL"); } if (buzzer_init() != OK) { - warnx("ERROR: Failed to initialize buzzer"); + warnx("ERROR: BUZZER INIT FAIL"); } mavlink_fd = open(MAVLINK_LOG_DEVICE, 0); -- cgit v1.2.3 From 76f7960d77046c33a771be49b57e32c957e7a2ef Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:43:56 +0200 Subject: Mavlink text feedback: Remove now unneeded audio tag for critical messages, make overall printing more efficient. Remove buffers where no buffers are needed. --- src/modules/commander/commander.cpp | 55 +++++++++++++++++-------------------- 1 file changed, 25 insertions(+), 30 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 85c9ccbaa..76cfd5feb 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -775,8 +775,9 @@ int commander_thread_main(int argc, char *argv[]) mavlink_log_info(mavlink_fd, "[cmd] dataman_id=%d, count=%u, current=%d", mission.dataman_id, mission.count, mission.current_seq); } else { - warnx("reading mission state failed"); - mavlink_log_info(mavlink_fd, "[cmd] reading mission state failed"); + const char *missionfail = "reading mission state failed"; + warnx("%s", missionfail); + mavlink_log_critical(mavlink_fd, missionfail); /* initialize mission state in dataman */ mission.dataman_id = 0; @@ -789,8 +790,6 @@ int commander_thread_main(int argc, char *argv[]) orb_publish(ORB_ID(offboard_mission), mission_pub, &mission); } - mavlink_log_info(mavlink_fd, "[cmd] started"); - int ret; pthread_attr_t commander_low_prio_attr; @@ -1083,7 +1082,7 @@ int commander_thread_main(int argc, char *argv[]) arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd)) { - mavlink_log_info(mavlink_fd, "[cmd] DISARMED by safety switch"); + mavlink_log_info(mavlink_fd, "DISARMED by safety switch"); arming_state_changed = true; } } @@ -1187,10 +1186,10 @@ int commander_thread_main(int argc, char *argv[]) status_changed = true; if (status.condition_landed) { - mavlink_log_critical(mavlink_fd, "#audio: LANDED"); + mavlink_log_critical(mavlink_fd, "LANDED MODE"); } else { - mavlink_log_critical(mavlink_fd, "#audio: IN AIR"); + mavlink_log_critical(mavlink_fd, "IN AIR MODE"); } } } @@ -1270,14 +1269,14 @@ int commander_thread_main(int argc, char *argv[]) /* if battery voltage is getting lower, warn using buzzer, etc. */ if (status.condition_battery_voltage_valid && status.battery_remaining < 0.25f && !low_battery_voltage_actions_done) { low_battery_voltage_actions_done = true; - mavlink_log_critical(mavlink_fd, "#audio: WARNING: LOW BATTERY"); + mavlink_log_critical(mavlink_fd, "LOW BATTERY, RETURN TO LAND ADVISED"); status.battery_warning = VEHICLE_BATTERY_WARNING_LOW; status_changed = true; } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.1f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) { /* critical battery voltage, this is rather an emergency, change state machine */ critical_battery_voltage_actions_done = true; - mavlink_log_critical(mavlink_fd, "#audio: EMERGENCY: CRITICAL BATTERY"); + mavlink_log_emergency(mavlink_fd, "CRITICAL BATTERY, LAND IMMEDIATELY"); status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL; if (armed.armed) { @@ -1339,12 +1338,12 @@ int commander_thread_main(int argc, char *argv[]) /* handle the case where RC signal was regained */ if (!status.rc_signal_found_once) { status.rc_signal_found_once = true; - mavlink_log_critical(mavlink_fd, "#audio: detected RC signal first time"); + mavlink_log_critical(mavlink_fd, "detected RC signal first time"); status_changed = true; } else { if (status.rc_signal_lost) { - mavlink_log_critical(mavlink_fd, "#audio: RC signal regained"); + mavlink_log_critical(mavlink_fd, "RC signal regained"); status_changed = true; } } @@ -1385,7 +1384,7 @@ int commander_thread_main(int argc, char *argv[]) * the system can be armed in auto if armed via the GCS. */ if (status.main_state != MAIN_STATE_MANUAL) { - print_reject_arm("#audio: NOT ARMING: Switch to MANUAL mode first."); + print_reject_arm("NOT ARMING: Switch to MANUAL mode first."); } else { arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, mavlink_fd); if (arming_ret == TRANSITION_CHANGED) { @@ -1405,16 +1404,16 @@ int commander_thread_main(int argc, char *argv[]) if (arming_ret == TRANSITION_CHANGED) { if (status.arming_state == ARMING_STATE_ARMED) { - mavlink_log_info(mavlink_fd, "[cmd] ARMED by RC"); + mavlink_log_info(mavlink_fd, "ARMED by RC"); } else { - mavlink_log_info(mavlink_fd, "[cmd] DISARMED by RC"); + mavlink_log_info(mavlink_fd, "DISARMED by RC"); } arming_state_changed = true; } else if (arming_ret == TRANSITION_DENIED) { /* DENIED here indicates bug in the commander */ - mavlink_log_critical(mavlink_fd, "ERROR: arming state transition denied"); + mavlink_log_critical(mavlink_fd, "arming state transition denied"); tune_negative(true); } @@ -1428,12 +1427,12 @@ int commander_thread_main(int argc, char *argv[]) } else if (main_res == TRANSITION_DENIED) { /* DENIED here indicates bug in the commander */ - mavlink_log_critical(mavlink_fd, "ERROR: main state transition denied"); + mavlink_log_critical(mavlink_fd, "main state transition denied"); } } else { if (!status.rc_signal_lost) { - mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: RC SIGNAL LOST"); + mavlink_log_critical(mavlink_fd, "RC SIGNAL LOST"); status.rc_signal_lost = true; status_changed = true; } @@ -1445,14 +1444,14 @@ int commander_thread_main(int argc, char *argv[]) if (hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) { /* handle the case where data link was regained */ if (telemetry_lost[i]) { - mavlink_log_critical(mavlink_fd, "#audio: data link %i regained", i); + mavlink_log_critical(mavlink_fd, "data link %i regained", i); telemetry_lost[i] = false; } have_link = true; } else { if (!telemetry_lost[i]) { - mavlink_log_critical(mavlink_fd, "#audio: data link %i lost", i); + mavlink_log_critical(mavlink_fd, "data link %i lost", i); telemetry_lost[i] = true; } } @@ -1467,7 +1466,7 @@ int commander_thread_main(int argc, char *argv[]) } else { if (!status.data_link_lost) { - mavlink_log_critical(mavlink_fd, "#audio: CRITICAL: ALL DATA LINKS LOST"); + mavlink_log_critical(mavlink_fd, "ALL DATA LINKS LOST"); status.data_link_lost = true; status_changed = true; } @@ -2010,15 +2009,13 @@ set_control_mode() } void -print_reject_mode(struct vehicle_status_s *status, const char *msg) +print_reject_mode(struct vehicle_status_s *status_local, const char *msg) { hrt_abstime t = hrt_absolute_time(); if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) { last_print_mode_reject_time = t; - char s[80]; - sprintf(s, "#audio: REJECT %s", msg); - mavlink_log_critical(mavlink_fd, s); + mavlink_log_critical(mavlink_fd, "REJECT %s", msg); /* only buzz if armed, because else we're driving people nuts indoors they really need to look at the leds as well. */ @@ -2033,9 +2030,7 @@ print_reject_arm(const char *msg) if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) { last_print_mode_reject_time = t; - char s[80]; - sprintf(s, "#audio: %s", msg); - mavlink_log_critical(mavlink_fd, s); + mavlink_log_critical(mavlink_fd, msg); tune_negative(true); } } @@ -2048,12 +2043,12 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul break; case VEHICLE_CMD_RESULT_DENIED: - mavlink_log_critical(mavlink_fd, "#audio: command denied: %u", cmd.command); + mavlink_log_critical(mavlink_fd, "command denied: %u", cmd.command); tune_negative(true); break; case VEHICLE_CMD_RESULT_FAILED: - mavlink_log_critical(mavlink_fd, "#audio: command failed: %u", cmd.command); + mavlink_log_critical(mavlink_fd, "command failed: %u", cmd.command); tune_negative(true); break; @@ -2064,7 +2059,7 @@ void answer_command(struct vehicle_command_s &cmd, enum VEHICLE_CMD_RESULT resul break; case VEHICLE_CMD_RESULT_UNSUPPORTED: - mavlink_log_critical(mavlink_fd, "#audio: command unsupported: %u", cmd.command); + mavlink_log_critical(mavlink_fd, "command unsupported: %u", cmd.command); tune_negative(true); break; -- cgit v1.2.3 From f2b30be92ae946e8e40faade6cb10edfb037fdaf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:44:27 +0200 Subject: commander status leds: Fix -Wshadow warning. --- src/modules/commander/commander.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 76cfd5feb..e5ea237fc 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1650,22 +1650,22 @@ check_valid(hrt_abstime timestamp, hrt_abstime timeout, bool valid_in, bool *val } void -control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_armed, bool changed) +control_status_leds(vehicle_status_s *status_local, const actuator_armed_s *actuator_armed, bool changed) { /* driving rgbled */ if (changed) { bool set_normal_color = false; /* set mode */ - if (status->arming_state == ARMING_STATE_ARMED) { + if (status_local->arming_state == ARMING_STATE_ARMED) { rgbled_set_mode(RGBLED_MODE_ON); set_normal_color = true; - } else if (status->arming_state == ARMING_STATE_ARMED_ERROR) { + } else if (status_local->arming_state == ARMING_STATE_ARMED_ERROR) { rgbled_set_mode(RGBLED_MODE_BLINK_FAST); rgbled_set_color(RGBLED_COLOR_RED); - } else if (status->arming_state == ARMING_STATE_STANDBY) { + } else if (status_local->arming_state == ARMING_STATE_STANDBY) { rgbled_set_mode(RGBLED_MODE_BREATHE); set_normal_color = true; @@ -1676,12 +1676,12 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a if (set_normal_color) { /* set color */ - if (status->battery_warning == VEHICLE_BATTERY_WARNING_LOW || status->failsafe) { + if (status_local->battery_warning == VEHICLE_BATTERY_WARNING_LOW || status_local->failsafe) { rgbled_set_color(RGBLED_COLOR_AMBER); /* VEHICLE_BATTERY_WARNING_CRITICAL handled as ARMING_STATE_ARMED_ERROR / ARMING_STATE_STANDBY_ERROR */ } else { - if (status->condition_local_position_valid) { + if (status_local->condition_local_position_valid) { rgbled_set_color(RGBLED_COLOR_GREEN); } else { @@ -1714,7 +1714,7 @@ control_status_leds(vehicle_status_s *status, const actuator_armed_s *actuator_a #endif /* give system warnings on error LED, XXX maybe add memory usage warning too */ - if (status->load > 0.95f) { + if (status_local->load > 0.95f) { if (leds_counter % 2 == 0) { led_toggle(LED_AMBER); } -- cgit v1.2.3 From 66d5bc20c095a4dbd937b21c4f5fc1a67205f2d6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:45:02 +0200 Subject: commander RC handling: Fix -Wshadow warnings. --- src/modules/commander/commander.cpp | 42 ++++++++++++++++++------------------- 1 file changed, 21 insertions(+), 21 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index e5ea237fc..0c4d48dea 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1727,16 +1727,16 @@ control_status_leds(vehicle_status_s *status_local, const actuator_armed_s *actu } transition_result_t -set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoint_s *sp_man) +set_main_state_rc(struct vehicle_status_s *status_local, struct manual_control_setpoint_s *sp_man) { /* set main state according to RC switches */ transition_result_t res = TRANSITION_DENIED; /* offboard switch overrides main switch */ if (sp_man->offboard_switch == SWITCH_POS_ON) { - res = main_state_transition(status, MAIN_STATE_OFFBOARD); + res = main_state_transition(status_local, MAIN_STATE_OFFBOARD); if (res == TRANSITION_DENIED) { - print_reject_mode(status, "OFFBOARD"); + print_reject_mode(status_local, "OFFBOARD"); } else { return res; @@ -1751,78 +1751,78 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin case SWITCH_POS_OFF: // MANUAL if (sp_man->acro_switch == SWITCH_POS_ON) { - res = main_state_transition(status, MAIN_STATE_ACRO); + res = main_state_transition(status_local, MAIN_STATE_ACRO); } else { - res = main_state_transition(status, MAIN_STATE_MANUAL); + res = main_state_transition(status_local, MAIN_STATE_MANUAL); } // TRANSITION_DENIED is not possible here break; case SWITCH_POS_MIDDLE: // ASSIST if (sp_man->posctl_switch == SWITCH_POS_ON) { - res = main_state_transition(status, MAIN_STATE_POSCTL); + res = main_state_transition(status_local, MAIN_STATE_POSCTL); if (res != TRANSITION_DENIED) { break; // changed successfully or already in this state } - print_reject_mode(status, "POSCTL"); + print_reject_mode(status_local, "POSCTL"); } // fallback to ALTCTL - res = main_state_transition(status, MAIN_STATE_ALTCTL); + res = main_state_transition(status_local, MAIN_STATE_ALTCTL); if (res != TRANSITION_DENIED) { break; // changed successfully or already in this mode } if (sp_man->posctl_switch != SWITCH_POS_ON) { - print_reject_mode(status, "ALTCTL"); + print_reject_mode(status_local, "ALTCTL"); } // fallback to MANUAL - res = main_state_transition(status, MAIN_STATE_MANUAL); + res = main_state_transition(status_local, MAIN_STATE_MANUAL); // TRANSITION_DENIED is not possible here break; case SWITCH_POS_ON: // AUTO if (sp_man->return_switch == SWITCH_POS_ON) { - res = main_state_transition(status, MAIN_STATE_AUTO_RTL); + res = main_state_transition(status_local, MAIN_STATE_AUTO_RTL); if (res != TRANSITION_DENIED) { break; // changed successfully or already in this state } - print_reject_mode(status, "AUTO_RTL"); + print_reject_mode(status_local, "AUTO_RTL"); // fallback to LOITER if home position not set - res = main_state_transition(status, MAIN_STATE_AUTO_LOITER); + res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER); if (res != TRANSITION_DENIED) { break; // changed successfully or already in this state } } else if (sp_man->loiter_switch == SWITCH_POS_ON) { - res = main_state_transition(status, MAIN_STATE_AUTO_LOITER); + res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER); if (res != TRANSITION_DENIED) { break; // changed successfully or already in this state } - print_reject_mode(status, "AUTO_LOITER"); + print_reject_mode(status_local, "AUTO_LOITER"); } else { - res = main_state_transition(status, MAIN_STATE_AUTO_MISSION); + res = main_state_transition(status_local, MAIN_STATE_AUTO_MISSION); if (res != TRANSITION_DENIED) { break; // changed successfully or already in this state } - print_reject_mode(status, "AUTO_MISSION"); + print_reject_mode(status_local, "AUTO_MISSION"); // fallback to LOITER if home position not set - res = main_state_transition(status, MAIN_STATE_AUTO_LOITER); + res = main_state_transition(status_local, MAIN_STATE_AUTO_LOITER); if (res != TRANSITION_DENIED) { break; // changed successfully or already in this state @@ -1830,21 +1830,21 @@ set_main_state_rc(struct vehicle_status_s *status, struct manual_control_setpoin } // fallback to POSCTL - res = main_state_transition(status, MAIN_STATE_POSCTL); + res = main_state_transition(status_local, MAIN_STATE_POSCTL); if (res != TRANSITION_DENIED) { break; // changed successfully or already in this state } // fallback to ALTCTL - res = main_state_transition(status, MAIN_STATE_ALTCTL); + res = main_state_transition(status_local, MAIN_STATE_ALTCTL); if (res != TRANSITION_DENIED) { break; // changed successfully or already in this state } // fallback to MANUAL - res = main_state_transition(status, MAIN_STATE_MANUAL); + res = main_state_transition(status_local, MAIN_STATE_MANUAL); // TRANSITION_DENIED is not possible here break; -- cgit v1.2.3 From afc8908d38ff2eaabc2ca35363ac04697152cb6b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:45:32 +0200 Subject: commander: More docs-only changes in headers. --- src/modules/commander/commander_helper.cpp | 10 ++++++---- src/modules/commander/commander_helper.h | 9 ++++++--- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index 80e6861f6..d5fe122cb 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -1,9 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. - * Author: Thomas Gubler - * Julian Oes - * Anton Babushkin + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -37,6 +34,11 @@ /** * @file commander_helper.cpp * Commander helper functions implementations + * + * @author Thomas Gubler + * @author Julian Oes + * @author Anton Babushkin + * */ #include diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h index e75f2592f..a49c9e263 100644 --- a/src/modules/commander/commander_helper.h +++ b/src/modules/commander/commander_helper.h @@ -1,8 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2013 PX4 Development Team. All rights reserved. - * Author: Thomas Gubler - * Julian Oes + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -36,6 +34,9 @@ /** * @file commander_helper.h * Commander helper functions definitions + * + * @author Thomas Gubler + * @author Julian Oes */ #ifndef COMMANDER_HELPER_H_ @@ -77,6 +78,8 @@ void rgbled_set_pattern(rgbled_pattern_t *pattern); * Use integral of current if battery capacity known (BAT_CAPACITY parameter set), * else use simple estimate based on voltage. * + * @param voltage the current battery voltage + * @param discharged the discharged capacity * @return the estimated remaining capacity in 0..1 */ float battery_remaining_estimate_voltage(float voltage, float discharged); -- cgit v1.2.3 From 7525c290f2cdfd058d54e5e6eb2d2e522d070889 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 11:46:36 +0200 Subject: commander: more text feedback improvements. --- src/modules/commander/state_machine_helper.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 363f5e8eb..87a60e7fd 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -87,7 +87,7 @@ static const bool arming_transitions[ARMING_STATE_MAX][ARMING_STATE_MAX] = { }; // You can index into the array with an arming_state_t in order to get it's textual representation -static const char *state_names[ARMING_STATE_MAX] = { +static const char * const state_names[ARMING_STATE_MAX] = { "ARMING_STATE_INIT", "ARMING_STATE_STANDBY", "ARMING_STATE_ARMED", @@ -160,7 +160,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current // Fail transition if we need safety switch press } else if (safety->safety_switch_available && !safety->safety_off) { - mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Press safety switch!"); + mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch!"); valid_transition = false; } @@ -625,7 +625,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) int fd = open(ACCEL_DEVICE_PATH, O_RDONLY); if (fd < 0) { - mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL SENSOR MISSING"); + mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL SENSOR MISSING"); failed = true; goto system_eval; } @@ -633,7 +633,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) ret = ioctl(fd, ACCELIOCSELFTEST, 0); if (ret != OK) { - mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL CALIBRATION"); + mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL CALIBRATION"); failed = true; goto system_eval; } @@ -647,14 +647,14 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) float accel_magnitude = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z); if (accel_magnitude < 4.0f || accel_magnitude > 15.0f /* m/s^2 */) { - mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL RANGE"); - mavlink_log_info(mavlink_fd, "#audio: hold still while arming"); + mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL RANGE"); + mavlink_log_critical(mavlink_fd, "hold still while arming"); /* this is frickin' fatal */ failed = true; goto system_eval; } } else { - mavlink_log_critical(mavlink_fd, "#audio: FAIL: ACCEL READ"); + mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL READ"); /* this is frickin' fatal */ failed = true; goto system_eval; @@ -667,7 +667,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) fd = open(AIRSPEED_DEVICE_PATH, O_RDONLY); if (fd <= 0) { - mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED SENSOR MISSING"); + mavlink_log_critical(mavlink_fd, "ARM FAIL: AIRSPEED SENSOR MISSING"); failed = true; goto system_eval; } @@ -678,11 +678,11 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) if (ret == sizeof(diff_pres)) { if (fabsf(diff_pres.differential_pressure_filtered_pa > 6.0f)) { - mavlink_log_critical(mavlink_fd, "#audio: WARNING AIRSPEED CALIBRATION MISSING"); + mavlink_log_critical(mavlink_fd, "ARM WARNING: AIRSPEED CALIBRATION MISSING"); // XXX do not make this fatal yet } } else { - mavlink_log_critical(mavlink_fd, "#audio: FAIL: AIRSPEED READ"); + mavlink_log_critical(mavlink_fd, "ARM FAIL: AIRSPEED READ"); /* this is frickin' fatal */ failed = true; goto system_eval; -- cgit v1.2.3 From 0d51230d4e3b87dd67819e594895b24a0a8a0306 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 12:04:43 +0200 Subject: commander: Final MAVLink text feedback cleanup --- src/modules/commander/state_machine_helper.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 87a60e7fd..56c59ad3d 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -171,16 +171,16 @@ arming_state_transition(struct vehicle_status_s *status, /// current // Fail transition if power is not good if (!status->condition_power_input_valid) { - mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Connect power module."); + mavlink_log_critical(mavlink_fd, "NOT ARMING: Connect power module."); valid_transition = false; } // Fail transition if power levels on the avionics rail // are measured but are insufficient - if (status->condition_power_input_valid && (status->avionics_power_rail_voltage > 0.0f) && - (status->avionics_power_rail_voltage < 4.9f)) { + if (status->condition_power_input_valid && ((status->avionics_power_rail_voltage > 0.0f) && + (status->avionics_power_rail_voltage < 4.9f))) { - mavlink_log_critical(mavlink_fd, "#audio: NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage); + mavlink_log_critical(mavlink_fd, "NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage); valid_transition = false; } } -- cgit v1.2.3 From a32577377b8d735c77ffaaee15e2bbfa74be703f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 12:38:43 +0200 Subject: EKF init improvements --- .../ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp | 8 ++++++++ src/modules/ekf_att_pos_estimator/estimator_23states.cpp | 16 +++++++++++----- 2 files changed, 19 insertions(+), 5 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index 5ce6bdb0a..ee1561280 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -610,6 +610,10 @@ FixedwingEstimator::check_filter_state() rep.health_flags |= (((uint8_t)ekf_report.posHealth) << 1); rep.health_flags |= (((uint8_t)ekf_report.hgtHealth) << 2); rep.health_flags |= (((uint8_t)!ekf_report.gyroOffsetsExcessive) << 3); + // rep.health_flags |= (((uint8_t)ekf_report.onGround) << 4); + // rep.health_flags |= (((uint8_t)ekf_report.staticMode) << 5); + // rep.health_flags |= (((uint8_t)ekf_report.useCompass) << 6); + // rep.health_flags |= (((uint8_t)ekf_report.useAirspeed) << 7); rep.timeout_flags |= (((uint8_t)ekf_report.velTimeout) << 0); rep.timeout_flags |= (((uint8_t)ekf_report.posTimeout) << 1); @@ -1246,6 +1250,10 @@ FixedwingEstimator::task_main() _ekf->FuseVelposNED(); } else if (!_gps_initialized) { + + // force static mode + _ekf->staticMode = true; + // Convert GPS measurements to Pos NE, hgt and Vel NED _ekf->velNED[0] = 0.0f; _ekf->velNED[1] = 0.0f; diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index f33a1d780..e83c37bbd 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -2206,7 +2206,7 @@ void AttPosEKF::calcLLH(float posNED[3], double &lat, double &lon, float &hgt, d void AttPosEKF::OnGroundCheck() { - onGround = (((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f) && (VtasMeas < 6.0f)); + onGround = (((sq(velNED[0]) + sq(velNED[1]) + sq(velNED[2])) < 4.0f) && (VtasMeas < 8.0f)); if (staticMode) { staticMode = (!refSet || (GPSstatus < GPS_FIX_3D)); } @@ -2806,12 +2806,18 @@ void AttPosEKF::InitializeDynamic(float (&initvelNED)[3], float declination) current_ekf_state.statesNaN = false; current_ekf_state.velHealth = true; - //current_ekf_state.posHealth = ?; - //current_ekf_state.hgtHealth = ?; + current_ekf_state.posHealth = true; + current_ekf_state.hgtHealth = true; current_ekf_state.velTimeout = false; - //current_ekf_state.posTimeout = ?; - //current_ekf_state.hgtTimeout = ?; + current_ekf_state.posTimeout = false; + current_ekf_state.hgtTimeout = false; + + fuseVelData = false; + fusePosData = false; + fuseHgtData = false; + fuseMagData = false; + fuseVtasData = false; // Fill variables with valid data velNED[0] = initvelNED[0]; -- cgit v1.2.3 From 744eed91dca8a5f2ad8ead7ffa812d25755bcc93 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 12:43:10 +0200 Subject: Fix calibration counter usage --- src/modules/commander/airspeed_calibration.cpp | 19 +++++++++++-------- 1 file changed, 11 insertions(+), 8 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index d52cafb8f..a2f11b14a 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -168,7 +168,7 @@ int do_airspeed_calibration(int mavlink_fd) calibration_counter = 0; /* just take a few samples and make sure pitot tubes are not reversed */ - while (calibration_counter < 10) { + while (calibration_counter < 300) { /* wait blocking for new data */ struct pollfd fds[1]; @@ -182,16 +182,19 @@ int do_airspeed_calibration(int mavlink_fd) float calibrated_pa = diff_pres.differential_pressure_raw_pa - diff_pres_offset; - if (fabsf(calibrated_pa) < 9.0f) { - mavlink_log_critical(mavlink_fd, "Create airflow on pitot (%.1f Pa, #h101)", - (double)calibrated_pa); - usleep(3000 * 1000); + if (fabsf(calibrated_pa) < 50.0f) { + if (calibration_counter % 20 == 0) { + mavlink_log_critical(mavlink_fd, "Create airflow on pitot (%d Pa, #h101)", + (int)calibrated_pa); + } + usleep(100 * 1000); + calibration_counter++; continue; } /* do not allow negative values */ if (calibrated_pa < 0.0f) { - mavlink_log_critical(mavlink_fd, "Negative val: swap static vs dynamic ports,restart"); + mavlink_log_critical(mavlink_fd, "%d Pa: swap static vs dynamic ports,restart", (int)calibrated_pa); close(diff_pres_sub); /* the user setup is wrong, wipe the calibration to force a proper re-calibration */ @@ -209,8 +212,8 @@ int do_airspeed_calibration(int mavlink_fd) close(diff_pres_sub); return ERROR; } else { - mavlink_log_info(mavlink_fd, "positive pressure: (%.1f Pa)", - (double)diff_pres.differential_pressure_raw_pa); + mavlink_log_info(mavlink_fd, "positive pressure: OK (%d Pa)", + (int)calibrated_pa); break; } -- cgit v1.2.3 From 8590d555b432f206e2b88893ea5198c1398aa99c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 12:44:57 +0200 Subject: Fix calibration counter usage, take every sample --- src/modules/commander/airspeed_calibration.cpp | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index a2f11b14a..10d04aae9 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -167,8 +167,8 @@ int do_airspeed_calibration(int mavlink_fd) calibration_counter = 0; - /* just take a few samples and make sure pitot tubes are not reversed */ - while (calibration_counter < 300) { + /* just take a few samples and make sure pitot tubes are not reversed, timeout after ~30 seconds */ + while (calibration_counter < 1500) { /* wait blocking for new data */ struct pollfd fds[1]; @@ -181,14 +181,13 @@ int do_airspeed_calibration(int mavlink_fd) orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); float calibrated_pa = diff_pres.differential_pressure_raw_pa - diff_pres_offset; + calibration_counter++; if (fabsf(calibrated_pa) < 50.0f) { - if (calibration_counter % 20 == 0) { + if (calibration_counter % 100 == 0) { mavlink_log_critical(mavlink_fd, "Create airflow on pitot (%d Pa, #h101)", (int)calibrated_pa); } - usleep(100 * 1000); - calibration_counter++; continue; } -- cgit v1.2.3 From c610050dc305884a704b51c00cfff5f2f9984bcb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 14:55:23 +0200 Subject: EKF hotfix: Add missing vector zero calls --- src/modules/ekf_att_pos_estimator/estimator_23states.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index f33a1d780..3da92b264 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -2280,7 +2280,7 @@ float AttPosEKF::ConstrainFloat(float val, float min, float max) } if (!isfinite(val)) { - ekf_debug("constrain: non-finite!"); + //ekf_debug("constrain: non-finite!"); } return ret; @@ -2920,6 +2920,8 @@ void AttPosEKF::ZeroVariables() correctedDelAng.zero(); summedDelAng.zero(); summedDelVel.zero(); + dAngIMU.zero(); + dVelIMU.zero(); lastGyroOffset.zero(); for (unsigned i = 0; i < data_buffer_size; i++) { -- cgit v1.2.3 From b4b3a2a2c68a523af5141a4452e533befc873384 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 14:58:57 +0200 Subject: EKF hotfix: Force zero initialization of vectors --- src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp | 4 ++-- src/modules/ekf_att_pos_estimator/estimator_23states.cpp | 2 +- src/modules/ekf_att_pos_estimator/estimator_utilities.h | 8 ++++++++ 3 files changed, 11 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index 5d768b73d..a835599e7 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -743,8 +743,8 @@ FixedwingEstimator::task_main() /* sets also parameters in the EKF object */ parameters_update(); - Vector3f lastAngRate = {0.0f, 0.0f, 0.0f}; - Vector3f lastAccel = {0.0f, 0.0f, 0.0f}; + Vector3f lastAngRate; + Vector3f lastAccel; /* wakeup source(s) */ struct pollfd fds[2]; diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index 3da92b264..a41b58250 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -73,7 +73,7 @@ void AttPosEKF::UpdateStrapdownEquationsNED() float qUpdated[4]; float quatMag; float deltaQuat[4]; - const Vector3f gravityNED = {0.0,0.0,GRAVITY_MSS}; + const Vector3f gravityNED(0.0f, 0.0f, GRAVITY_MSS); // Remove sensor bias errors correctedDelAng.x = dAngIMU.x - states[10]; diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.h b/src/modules/ekf_att_pos_estimator/estimator_utilities.h index 5648cb05c..0cafdc808 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_utilities.h +++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.h @@ -19,6 +19,14 @@ public: float y; float z; + Vector3f() { zero(); } + + Vector3f(float a, float b, float c) : + x(a), + y(b), + z(c) + {} + float length(void) const; void zero(void); }; -- cgit v1.2.3 From 3d505c6f42779eddc983e0f1a25c59d998cdd041 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 15:38:42 +0200 Subject: EKF hotfix: Force all fields to initialized --- .../ekf_att_pos_estimator/estimator_23states.cpp | 153 +++++++++++++++------ 1 file changed, 113 insertions(+), 40 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index a41b58250..7f9486eb5 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -5,47 +5,120 @@ #define EKF_COVARIANCE_DIVERGED 1.0e8f -AttPosEKF::AttPosEKF() - - /* NOTE: DO NOT initialize class members here. Use ZeroVariables() - * instead to allow clean in-air re-initialization. - */ +AttPosEKF::AttPosEKF() : + covTimeStepMax(0.0f), + covDelAngMax(0.0f), + rngFinderPitch(0.0f), + a1(0.0f), + a2(0.0f), + a3(0.0f), + yawVarScale(0.0f), + windVelSigma(0.0f), + dAngBiasSigma(0.0f), + dVelBiasSigma(0.0f), + magEarthSigma(0.0f), + magBodySigma(0.0f), + gndHgtSigma(0.0f), + vneSigma(0.0f), + vdSigma(0.0f), + posNeSigma(0.0f), + posDSigma(0.0f), + magMeasurementSigma(0.0f), + airspeedMeasurementSigma(0.0f), + gyroProcessNoise(0.0f), + accelProcessNoise(0.0f), + EAS2TAS(1.0f), + magstate{}, + resetMagState{}, + KH{}, + KHP{}, + P{}, + Kfusion{}, + states{}, + resetStates{}, + storedStates{}, + statetimeStamp{}, + statesAtVelTime{}, + statesAtPosTime{}, + statesAtHgtTime{}, + statesAtMagMeasTime{}, + statesAtVtasMeasTime{}, + statesAtRngTime{}, + statesAtOptFlowTime{}, + correctedDelAng(), + correctedDelVel(), + summedDelAng(), + summedDelVel(), + accNavMag(), + earthRateNED(), + angRate(), + lastGyroOffset(), + delAngTotal(), + Tbn(), + Tnb(), + accel(), + dVelIMU(), + dAngIMU(), + dtIMU(0), + fusionModeGPS(0), + innovVelPos{}, + varInnovVelPos{}, + velNED{}, + accelGPSNED{}, + posNE{}, + hgtMea(0.0f), + baroHgtOffset(0.0f), + rngMea(0.0f), + innovMag{}, + varInnovMag{}, + magData{}, + losData{}, + innovVtas(0.0f), + innovRng(0.0f), + innovOptFlow{}, + varInnovOptFlow{}, + varInnovVtas(0.0f), + varInnovRng(0.0f), + VtasMeas(0.0f), + magDeclination(0.0f), + latRef(0.0f), + lonRef(-M_PI_F), + hgtRef(0.0f), + refSet(false), + magBias(), + covSkipCount(0), + gpsLat(0.0), + gpsLon(-M_PI), + gpsHgt(0.0f), + GPSstatus(0), + baroHgt(0.0f), + statesInitialised(false), + fuseVelData(false), + fusePosData(false), + fuseHgtData(false), + fuseMagData(false), + fuseVtasData(false), + fuseRngData(false), + fuseOptFlowData(false), + + inhibitWindStates(true), + inhibitMagStates(true), + inhibitGndHgtState(true), + + onGround(true), + staticMode(true), + useAirspeed(true), + useCompass(true), + useRangeFinder(false), + useOpticalFlow(false), + + ekfDiverged(false), + lastReset(0), + current_ekf_state{}, + last_ekf_error{}, + numericalProtection(true), + storeIndex(0) { - summedDelAng.zero(); - summedDelVel.zero(); - - fusionModeGPS = 0; - fuseVelData = false; - fusePosData = false; - fuseHgtData = false; - fuseMagData = false; - fuseVtasData = false; - onGround = true; - staticMode = true; - useAirspeed = true; - useCompass = true; - useRangeFinder = true; - useOpticalFlow = true; - numericalProtection = true; - refSet = false; - storeIndex = 0; - gpsHgt = 0.0f; - baroHgt = 0.0f; - GPSstatus = 0; - VtasMeas = 0.0f; - magDeclination = 0.0f; - dAngIMU.zero(); - dVelIMU.zero(); - velNED[0] = 0.0f; - velNED[1] = 0.0f; - velNED[2] = 0.0f; - accelGPSNED[0] = 0.0f; - accelGPSNED[1] = 0.0f; - accelGPSNED[2] = 0.0f; - delAngTotal.zero(); - ekfDiverged = false; - lastReset = 0; - memset(&last_ekf_error, 0, sizeof(last_ekf_error)); memset(¤t_ekf_state, 0, sizeof(current_ekf_state)); ZeroVariables(); -- cgit v1.2.3 From e8855423bea0938c607ed2ab8bde5ebec094b5a6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 15:39:35 +0200 Subject: EKF hotfix: Remove unused variables, use default initializer list for vectors --- src/modules/ekf_att_pos_estimator/estimator_23states.h | 2 -- src/modules/ekf_att_pos_estimator/estimator_utilities.h | 4 +--- 2 files changed, 1 insertion(+), 5 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.h b/src/modules/ekf_att_pos_estimator/estimator_23states.h index ff311649a..faa6735ca 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.h +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.h @@ -172,8 +172,6 @@ public: unsigned covSkipCount; // Number of state prediction frames (IMU daya updates to skip before doing the covariance prediction // GPS input data variables - float gpsCourse; - float gpsVelD; double gpsLat; double gpsLon; float gpsHgt; diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.h b/src/modules/ekf_att_pos_estimator/estimator_utilities.h index 0cafdc808..6d1f47b68 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_utilities.h +++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.h @@ -19,9 +19,7 @@ public: float y; float z; - Vector3f() { zero(); } - - Vector3f(float a, float b, float c) : + Vector3f(float a=0.0f, float b=0.0f, float c=0.0f) : x(a), y(b), z(c) -- cgit v1.2.3 From d4a867071a2183069d8902292357133856cd2ffd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 15:44:15 +0200 Subject: airspeed: Better calibration messages --- src/modules/commander/airspeed_calibration.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 10d04aae9..469f15632 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -193,7 +193,7 @@ int do_airspeed_calibration(int mavlink_fd) /* do not allow negative values */ if (calibrated_pa < 0.0f) { - mavlink_log_critical(mavlink_fd, "%d Pa: swap static vs dynamic ports,restart", (int)calibrated_pa); + mavlink_log_critical(mavlink_fd, "%d Pa: swap static and dynamic ports!", (int)calibrated_pa); close(diff_pres_sub); /* the user setup is wrong, wipe the calibration to force a proper re-calibration */ @@ -206,9 +206,12 @@ int do_airspeed_calibration(int mavlink_fd) } /* save */ + mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 0); (void)param_save_default(); close(diff_pres_sub); + + mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name); return ERROR; } else { mavlink_log_info(mavlink_fd, "positive pressure: OK (%d Pa)", -- cgit v1.2.3 From a1c5f87deaf3e8626f838b191be5b57f33d3dc46 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 16:26:47 +0200 Subject: Fix C++ warnings --- .../ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp | 13 ++++++++++++- src/modules/ekf_att_pos_estimator/estimator_utilities.cpp | 7 +++++-- 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index a835599e7..bc40ce3c4 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -112,6 +112,10 @@ public: */ FixedwingEstimator(); + /* we do not want people ever copying this class */ + FixedwingEstimator(const FixedwingEstimator& that) = delete; + FixedwingEstimator operator=(const FixedwingEstimator&) = delete; + /** * Destructor, also kills the sensors task. */ @@ -362,9 +366,10 @@ FixedwingEstimator::FixedwingEstimator() : _mag_offsets({}), #ifdef SENSOR_COMBINED_SUB - _sensor_combined({}), + _sensor_combined{}, #endif + _pos_ref{}, _baro_ref(0.0f), _baro_ref_offset(0.0f), _baro_gps_offset(0.0f), @@ -381,12 +386,18 @@ FixedwingEstimator::FixedwingEstimator() : /* states */ _baro_init(false), _gps_initialized(false), + _gps_start_time(0), + _filter_start_time(0), + _last_sensor_timestamp(0), + _last_run(0), _gyro_valid(false), _accel_valid(false), _mag_valid(false), _ekf_logging(true), _debug(0), _mavlink_fd(-1), + _parameters{}, + _parameter_handles{}, _ekf(nullptr), _velocity_xy_filtered(0.0f), _velocity_z_filtered(0.0f), diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp index 29a8c8d1e..77cc1eeeb 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.cpp @@ -45,8 +45,11 @@ void Vector3f::zero(void) z = 0.0f; } -Mat3f::Mat3f() { - identity(); +Mat3f::Mat3f() : + x{1.0f, 0.0f, 0.0f}, + y{0.0f, 1.0f, 0.0f}, + z{0.0f, 0.0f, 1.0f} +{ } void Mat3f::identity() { -- cgit v1.2.3 From 17c5e925fb928d9c0926d8495a2db7a7b464c15f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 16:27:08 +0200 Subject: Enable C++ warnings for EKF --- src/modules/ekf_att_pos_estimator/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/ekf_att_pos_estimator/module.mk b/src/modules/ekf_att_pos_estimator/module.mk index dc5220bf0..36d854ddd 100644 --- a/src/modules/ekf_att_pos_estimator/module.mk +++ b/src/modules/ekf_att_pos_estimator/module.mk @@ -41,3 +41,5 @@ SRCS = ekf_att_pos_estimator_main.cpp \ ekf_att_pos_estimator_params.c \ estimator_23states.cpp \ estimator_utilities.cpp + +EXTRACXXFLAGS = -Weffc++ -- cgit v1.2.3 From f219c05f0f53ee8b8f5dbe24318678be6c255dd9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 16:27:30 +0200 Subject: Fix a set of C++ warnings in mathlib --- src/lib/mathlib/math/Matrix.hpp | 23 ++++++++++++++--------- src/lib/mathlib/math/Vector.hpp | 9 ++++++--- 2 files changed, 20 insertions(+), 12 deletions(-) diff --git a/src/lib/mathlib/math/Matrix.hpp b/src/lib/mathlib/math/Matrix.hpp index ea0cf4ca1..c2109b479 100644 --- a/src/lib/mathlib/math/Matrix.hpp +++ b/src/lib/mathlib/math/Matrix.hpp @@ -69,27 +69,32 @@ public: /** * trivial ctor - * note that this ctor will not initialize elements + * Initializes the elements to zero. */ - MatrixBase() { - arm_mat = {M, N, &data[0][0]}; + MatrixBase() : + data{}, + arm_mat{M, N, &data[0][0]} + { } /** * copyt ctor */ - MatrixBase(const MatrixBase &m) { - arm_mat = {M, N, &data[0][0]}; + MatrixBase(const MatrixBase &m) : + arm_mat{M, N, &data[0][0]} + { memcpy(data, m.data, sizeof(data)); } - MatrixBase(const float *d) { - arm_mat = {M, N, &data[0][0]}; + MatrixBase(const float *d) : + arm_mat{M, N, &data[0][0]} + { memcpy(data, d, sizeof(data)); } - MatrixBase(const float d[M][N]) { - arm_mat = {M, N, &data[0][0]}; + MatrixBase(const float d[M][N]) : + arm_mat{M, N, &data[0][0]} + { memcpy(data, d, sizeof(data)); } diff --git a/src/lib/mathlib/math/Vector.hpp b/src/lib/mathlib/math/Vector.hpp index c7323c215..5017b7c79 100644 --- a/src/lib/mathlib/math/Vector.hpp +++ b/src/lib/mathlib/math/Vector.hpp @@ -69,10 +69,13 @@ public: /** * trivial ctor - * note that this ctor will not initialize elements + * initializes elements to zero */ - VectorBase() { - arm_col = {N, 1, &data[0]}; + VectorBase() : + data{}, + arm_col{N, 1, &data[0]} + { + } /** -- cgit v1.2.3 From 36c20681621c2b99c1486aa0e3700cdbd86bd42d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 22:42:34 +0200 Subject: Removed spurious submodule entry --- src/modules/ekf_att_pos_estimator/InertialNav | 1 - 1 file changed, 1 deletion(-) delete mode 160000 src/modules/ekf_att_pos_estimator/InertialNav diff --git a/src/modules/ekf_att_pos_estimator/InertialNav b/src/modules/ekf_att_pos_estimator/InertialNav deleted file mode 160000 index 8b65d755b..000000000 --- a/src/modules/ekf_att_pos_estimator/InertialNav +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 8b65d755b8c4834f90a323172c25d91c45068e21 -- cgit v1.2.3 From 1dffa750d8b91af8f600ba4cf1fbcdcc61edf80f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 22:44:32 +0200 Subject: added detailed print --- src/modules/commander/airspeed_calibration.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 469f15632..bc12037c3 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -162,6 +162,8 @@ int do_airspeed_calibration(int mavlink_fd) return ERROR; } + mavlink_log_critical(mavlink_fd, "Stored offset of %d Pa", (int)calibrated_pa); + /* wait 500 ms to ensure parameter propagated through the system */ usleep(500 * 1000); -- cgit v1.2.3 From 56ad0c708d2695515489802676cc295f040b3606 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 13 Jul 2014 22:53:50 +0200 Subject: Fixed compile error --- src/modules/commander/airspeed_calibration.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index bc12037c3..2e3f89e65 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -162,7 +162,7 @@ int do_airspeed_calibration(int mavlink_fd) return ERROR; } - mavlink_log_critical(mavlink_fd, "Stored offset of %d Pa", (int)calibrated_pa); + mavlink_log_critical(mavlink_fd, "Stored offset of %d Pa", (int)diff_pres_offset); /* wait 500 ms to ensure parameter propagated through the system */ usleep(500 * 1000); -- cgit v1.2.3 From 7968c6864e1255b4a65427187119aec2c3fc7ae0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 14 Jul 2014 00:04:02 +0200 Subject: Force update of offset, do not add offset in final value --- src/modules/commander/airspeed_calibration.cpp | 21 +++++++++++++++------ src/modules/commander/state_machine_helper.cpp | 4 ++-- 2 files changed, 17 insertions(+), 8 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 2e3f89e65..ea81ac6a6 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -140,6 +140,16 @@ int do_airspeed_calibration(int mavlink_fd) if (isfinite(diff_pres_offset)) { + int fd_scale = open(AIRSPEED_DEVICE_PATH, 0); + airscale.offset_pa = diff_pres_offset; + if (fd_scale > 0) { + if (OK != ioctl(fd_scale, AIRSPEEDIOCSSCALE, (long unsigned int)&airscale)) { + mavlink_log_critical(mavlink_fd, "airspeed offset update failed"); + } + + close(fd_scale); + } + if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) { mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG); close(diff_pres_sub); @@ -182,20 +192,19 @@ int do_airspeed_calibration(int mavlink_fd) if (poll_ret) { orb_copy(ORB_ID(differential_pressure), diff_pres_sub, &diff_pres); - float calibrated_pa = diff_pres.differential_pressure_raw_pa - diff_pres_offset; calibration_counter++; - if (fabsf(calibrated_pa) < 50.0f) { + if (fabsf(diff_pres.differential_pressure_raw_pa) < 50.0f) { if (calibration_counter % 100 == 0) { mavlink_log_critical(mavlink_fd, "Create airflow on pitot (%d Pa, #h101)", - (int)calibrated_pa); + (int)diff_pres.differential_pressure_raw_pa); } continue; } /* do not allow negative values */ - if (calibrated_pa < 0.0f) { - mavlink_log_critical(mavlink_fd, "%d Pa: swap static and dynamic ports!", (int)calibrated_pa); + if (diff_pres.differential_pressure_raw_pa < 0.0f) { + mavlink_log_critical(mavlink_fd, "%d Pa: swap static and dynamic ports!", (int)diff_pres.differential_pressure_raw_pa); close(diff_pres_sub); /* the user setup is wrong, wipe the calibration to force a proper re-calibration */ @@ -217,7 +226,7 @@ int do_airspeed_calibration(int mavlink_fd) return ERROR; } else { mavlink_log_info(mavlink_fd, "positive pressure: OK (%d Pa)", - (int)calibrated_pa); + (int)diff_pres.differential_pressure_raw_pa); break; } diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 09ea12c38..372ba9d7d 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -668,8 +668,8 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) struct airspeed_s airspeed; - if (ret = orb_copy(ORB_ID(airspeed), fd, &airspeed) || - hrt_elapsed_time(&airspeed.timestamp) > 50 * 1000) { + if ((ret = orb_copy(ORB_ID(airspeed), fd, &airspeed)) || + (hrt_elapsed_time(&airspeed.timestamp) > (50 * 1000))) { mavlink_log_critical(mavlink_fd, "ARM FAIL: AIRSPEED SENSOR MISSING"); failed = true; goto system_eval; -- cgit v1.2.3 From 180b83cc6dc6872c5248993b5409ac835a201114 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 14 Jul 2014 00:41:12 +0200 Subject: Better analog error handling --- src/modules/commander/airspeed_calibration.cpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index ea81ac6a6..92d50a025 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -94,9 +94,17 @@ int do_airspeed_calibration(int mavlink_fd) } if (!paramreset_successful) { - warn("FAILED to reset - assuming analog"); - mavlink_log_critical(mavlink_fd, "If analog sens, retry with [SENS_DPRES_ANSC=1000]"); + /* only warn if analog scaling is zero */ + float analog_scaling = 0.0f; + param_get(param_find("SENS_DPRES_ANSC"), &(analog_scaling)) + if (fabsf(analog_scaling) < 0.1f) { + mavlink_log_critical(mavlink_fd, "If analog sens, retry with [SENS_DPRES_ANSC=1000]"); + close(diff_pres_sub); + return ERROR; + } + + /* set scaling offset parameter */ if (param_set(param_find("SENS_DPRES_OFF"), &(diff_pres_offset))) { mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG); close(diff_pres_sub); -- cgit v1.2.3 From ec8d395a2d270bd77e873f616a53ee0771c94165 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 14 Jul 2014 08:07:30 +0200 Subject: build fix --- src/modules/commander/airspeed_calibration.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 92d50a025..423d88682 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -97,7 +97,7 @@ int do_airspeed_calibration(int mavlink_fd) /* only warn if analog scaling is zero */ float analog_scaling = 0.0f; - param_get(param_find("SENS_DPRES_ANSC"), &(analog_scaling)) + param_get(param_find("SENS_DPRES_ANSC"), &(analog_scaling)); if (fabsf(analog_scaling) < 0.1f) { mavlink_log_critical(mavlink_fd, "If analog sens, retry with [SENS_DPRES_ANSC=1000]"); close(diff_pres_sub); -- cgit v1.2.3 From 5f176d14fed9ace9f5265a40b7ace1e6d00a7690 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 14 Jul 2014 08:11:33 +0200 Subject: ekf: Only return from start handler with all allocations done --- .../ekf_att_pos_estimator_main.cpp | 25 ++++++++++++++++++++-- 1 file changed, 23 insertions(+), 2 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index a835599e7..247814a7e 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -124,6 +124,13 @@ public: */ int start(); + /** + * Task status + * + * @return true if the mainloop is running + */ + bool task_running() { return _task_running; } + /** * Print the current status. */ @@ -151,7 +158,8 @@ public: private: bool _task_should_exit; /**< if true, sensor task should exit */ - int _estimator_task; /**< task handle for sensor task */ + bool _task_running; /**< if true, task is running in its mainloop */ + int _estimator_task; /**< task handle for sensor task */ #ifndef SENSOR_COMBINED_SUB int _gyro_sub; /**< gyro sensor subscription */ int _accel_sub; /**< accel sensor subscription */ @@ -313,12 +321,13 @@ namespace estimator #endif static const int ERROR = -1; -FixedwingEstimator *g_estimator; +FixedwingEstimator *g_estimator = nullptr; } FixedwingEstimator::FixedwingEstimator() : _task_should_exit(false), + _task_running(false), _estimator_task(-1), /* subscriptions */ @@ -772,6 +781,8 @@ FixedwingEstimator::task_main() _gps.vel_e_m_s = 0.0f; _gps.vel_d_m_s = 0.0f; + _task_running = true; + while (!_task_should_exit) { /* wait for up to 500ms for data */ @@ -1518,6 +1529,8 @@ FixedwingEstimator::task_main() perf_end(_loop_perf); } + _task_running = false; + warnx("exiting.\n"); _estimator_task = -1; @@ -1670,6 +1683,14 @@ int ekf_att_pos_estimator_main(int argc, char *argv[]) err(1, "start failed"); } + /* avoid memory fragmentation by not exiting start handler until the task has fully started */ + while (estimator::g_estimator == nullptr || !estimator::g_estimator->task_running()) { + usleep(50000); + printf("."); + fflush(stdout); + } + printf("\n"); + exit(0); } -- cgit v1.2.3 From 8a0e83c9cd9a54f09c6bc5c2c89917d87a451192 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 14 Jul 2014 08:11:55 +0200 Subject: fw att ctrl: Only return from start handler with all allocations done --- src/modules/fw_att_control/fw_att_control_main.cpp | 28 ++++++++++++++++++---- 1 file changed, 24 insertions(+), 4 deletions(-) diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp index 3cd4ce928..4cdba735a 100644 --- a/src/modules/fw_att_control/fw_att_control_main.cpp +++ b/src/modules/fw_att_control/fw_att_control_main.cpp @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2013 PX4 Development Team. All rights reserved. - * Author: Lorenz Meier + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -99,13 +98,21 @@ public: /** * Start the sensors task. * - * @return OK on success. + * @return OK on success. */ int start(); + /** + * Task status + * + * @return true if the mainloop is running + */ + bool task_running() { return _task_running; } + private: bool _task_should_exit; /**< if true, sensor task should exit */ + bool _task_running; /**< if true, task is running in its mainloop */ int _control_task; /**< task handle for sensor task */ int _att_sub; /**< vehicle attitude subscription */ @@ -276,6 +283,7 @@ private: * Main sensor collection task. */ void task_main(); + }; namespace att_control @@ -287,12 +295,13 @@ namespace att_control #endif static const int ERROR = -1; -FixedwingAttitudeControl *g_control; +FixedwingAttitudeControl *g_control = nullptr; } FixedwingAttitudeControl::FixedwingAttitudeControl() : _task_should_exit(false), + _task_running(false), _control_task(-1), /* subscriptions */ @@ -598,6 +607,8 @@ FixedwingAttitudeControl::task_main() fds[1].fd = _att_sub; fds[1].events = POLLIN; + _task_running = true; + while (!_task_should_exit) { static int loop_counter = 0; @@ -921,6 +932,7 @@ FixedwingAttitudeControl::task_main() warnx("exiting.\n"); _control_task = -1; + _task_running = false; _exit(0); } @@ -966,6 +978,14 @@ int fw_att_control_main(int argc, char *argv[]) err(1, "start failed"); } + /* avoid memory fragmentation by not exiting start handler until the task has fully started */ + while (att_control::g_control == nullptr || !att_control::g_control->task_running()) { + usleep(50000); + printf("."); + fflush(stdout); + } + printf("\n"); + exit(0); } -- cgit v1.2.3 From efa5d8f57f303a51f618b7c108f516d5e857c3b3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 14 Jul 2014 08:12:17 +0200 Subject: fw pos ctrl: Only return from start handler with all allocations done --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 26 +++++++++++++++++++--- 1 file changed, 23 insertions(+), 3 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 98ccd09a5..08c996ebc 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -1,7 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2013 PX4 Development Team. All rights reserved. - * Author: Lorenz Meier + * Copyright (c) 2013, 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -120,10 +119,18 @@ public: */ int start(); + /** + * Task status + * + * @return true if the mainloop is running + */ + bool task_running() { return _task_running; } + private: int _mavlink_fd; bool _task_should_exit; /**< if true, sensor task should exit */ + bool _task_running; /**< if true, task is running in its mainloop */ int _control_task; /**< task handle for sensor task */ int _global_pos_sub; @@ -391,13 +398,14 @@ namespace l1_control #endif static const int ERROR = -1; -FixedwingPositionControl *g_control; +FixedwingPositionControl *g_control = nullptr; } FixedwingPositionControl::FixedwingPositionControl() : _mavlink_fd(-1), _task_should_exit(false), + _task_running(false), _control_task(-1), /* subscriptions */ @@ -1290,6 +1298,8 @@ FixedwingPositionControl::task_main() fds[1].fd = _global_pos_sub; fds[1].events = POLLIN; + _task_running = true; + while (!_task_should_exit) { /* wait for up to 500ms for data */ @@ -1390,6 +1400,8 @@ FixedwingPositionControl::task_main() perf_end(_loop_perf); } + _task_running = false; + warnx("exiting.\n"); _control_task = -1; @@ -1478,6 +1490,14 @@ int fw_pos_control_l1_main(int argc, char *argv[]) err(1, "start failed"); } + /* avoid memory fragmentation by not exiting start handler until the task has fully started */ + while (l1_control::g_control == nullptr || !l1_control::g_control->task_running()) { + usleep(50000); + printf("."); + fflush(stdout); + } + printf("\n"); + exit(0); } -- cgit v1.2.3 From 9ce7820e419d2ffa379fb7a3cc168f500623fa3d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 14 Jul 2014 08:32:51 +0200 Subject: Make instructions in commander more obvious for airspeed calibration --- src/modules/commander/airspeed_calibration.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 423d88682..598cfe9e2 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -180,15 +180,16 @@ int do_airspeed_calibration(int mavlink_fd) return ERROR; } - mavlink_log_critical(mavlink_fd, "Stored offset of %d Pa", (int)diff_pres_offset); + mavlink_log_critical(mavlink_fd, "Offset of %d Pa, create airflow now!", (int)diff_pres_offset); /* wait 500 ms to ensure parameter propagated through the system */ usleep(500 * 1000); calibration_counter = 0; + const int maxcount = 3000; /* just take a few samples and make sure pitot tubes are not reversed, timeout after ~30 seconds */ - while (calibration_counter < 1500) { + while (calibration_counter < maxcount) { /* wait blocking for new data */ struct pollfd fds[1]; @@ -204,7 +205,7 @@ int do_airspeed_calibration(int mavlink_fd) if (fabsf(diff_pres.differential_pressure_raw_pa) < 50.0f) { if (calibration_counter % 100 == 0) { - mavlink_log_critical(mavlink_fd, "Create airflow on pitot (%d Pa, #h101)", + mavlink_log_critical(mavlink_fd, "Missing airflow! (%d, wanted: 50 Pa, #h101)", (int)diff_pres.differential_pressure_raw_pa); } continue; @@ -212,6 +213,8 @@ int do_airspeed_calibration(int mavlink_fd) /* do not allow negative values */ if (diff_pres.differential_pressure_raw_pa < 0.0f) { + mavlink_log_info(mavlink_fd, "negative pressure: ERROR (%d Pa)", + (int)diff_pres.differential_pressure_raw_pa); mavlink_log_critical(mavlink_fd, "%d Pa: swap static and dynamic ports!", (int)diff_pres.differential_pressure_raw_pa); close(diff_pres_sub); @@ -246,6 +249,12 @@ int do_airspeed_calibration(int mavlink_fd) } } + if (calibration_counter == maxcount) { + mavlink_log_critical(mavlink_fd, CAL_FAILED_MSG, sensor_name); + close(diff_pres_sub); + return ERROR; + } + mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 100); mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name); -- cgit v1.2.3 From f3549d775cb049bcde93c3e860c3adbad3763364 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 14 Jul 2014 08:33:35 +0200 Subject: Airspeed driver: Use the known sensor offset for raw value as well --- src/drivers/ets_airspeed/ets_airspeed.cpp | 3 +++ src/drivers/meas_airspeed/meas_airspeed.cpp | 5 ++++- 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index d1a9fa57c..c15a0cee4 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -172,6 +172,9 @@ ETSAirspeed::collect() diff_pres_pa = diff_pres_pa_raw - _diff_pres_offset; } + // The raw value still should be compensated for the known offset + diff_pres_pa_raw -= _diff_pres_offset; + // Track maximum differential pressure measured (so we can work out top speed). if (diff_pres_pa > _max_differential_pressure_pa) { _max_differential_pressure_pa = diff_pres_pa; diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 7763f1057..07611f903 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -225,7 +225,10 @@ MEASAirspeed::collect() // correct for 5V rail voltage if possible voltage_correction(diff_press_pa_raw, temperature); - float diff_press_pa = fabsf(diff_press_pa_raw - _diff_pres_offset); + // the raw value still should be compensated for the known offset + diff_press_pa_raw -= _diff_pres_offset; + + float diff_press_pa = fabsf(diff_press_pa_raw); /* note that we return both the absolute value with offset -- cgit v1.2.3 From 83652794c7709ee8058587a99e81826d4959ed49 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 15 Jul 2014 00:06:24 +0200 Subject: Add a mixer for the Phantom so it can be uniquely adjusted for this airframe. --- ROMFS/px4fmu_common/init.d/3031_phantom | 2 +- ROMFS/px4fmu_common/mixers/phantom.mix | 69 +++++++++++++++++++++++++++++++++ 2 files changed, 70 insertions(+), 1 deletion(-) create mode 100644 ROMFS/px4fmu_common/mixers/phantom.mix diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom index d05c3174f..654b0bdab 100644 --- a/ROMFS/px4fmu_common/init.d/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/3031_phantom @@ -36,7 +36,7 @@ then param set FW_T_TIME_CONST 5 fi -set MIXER FMU_Q +set MIXER phantom # Provide ESC a constant 1000 us pulse set PWM_OUTPUTS 4 diff --git a/ROMFS/px4fmu_common/mixers/phantom.mix b/ROMFS/px4fmu_common/mixers/phantom.mix new file mode 100644 index 000000000..7fe6dc055 --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/phantom.mix @@ -0,0 +1,69 @@ +Delta-wing mixer for PX4FMU +=========================== + +Designed for the Phantom FX-61 + +This file defines mixers suitable for controlling a delta wing aircraft using +PX4/Pixhawk. The configuration assumes the elevon servos are connected to +servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is +assumed to be unused. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch) and 3 (thrust). + +See the README for more information on the scaler format. + +Elevon mixers +------------- +Three scalers total (output, roll, pitch). + +On the assumption that the two elevon servos are physically reversed, the pitch +input is inverted between the two servos. + +The scaling factor are set so that pitch will have more travel than roll. + +M: 2 +O: 10000 10000 0 -10000 10000 +S: 0 0 -6000 -6000 0 -10000 10000 +S: 0 1 6500 6500 0 -10000 10000 + +M: 2 +O: 10000 10000 0 -10000 10000 +S: 0 0 -6000 -6000 0 -10000 10000 +S: 0 1 -6500 -6500 0 -10000 10000 + +Output 2 +-------- +This mixer is empty. + +Z: + +Motor speed mixer +----------------- +Two scalers total (output, thrust). + +This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1) +range. Inputs below zero are treated as zero. + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + +Gimbal / flaps / payload mixer for last four channels +----------------------------------------------------- + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 4 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 5 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 6 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 7 10000 10000 0 -10000 10000 -- cgit v1.2.3 From 9f837267de861cfd8313984f2ec64b8482a72161 Mon Sep 17 00:00:00 2001 From: Simon Wilks Date: Tue, 15 Jul 2014 00:10:08 +0200 Subject: Updated the comments. --- ROMFS/px4fmu_common/mixers/phantom.mix | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/ROMFS/px4fmu_common/mixers/phantom.mix b/ROMFS/px4fmu_common/mixers/phantom.mix index 7fe6dc055..00c37a16c 100644 --- a/ROMFS/px4fmu_common/mixers/phantom.mix +++ b/ROMFS/px4fmu_common/mixers/phantom.mix @@ -1,7 +1,5 @@ -Delta-wing mixer for PX4FMU -=========================== - -Designed for the Phantom FX-61 +Phantom FX-61 mixer +=================== This file defines mixers suitable for controlling a delta wing aircraft using PX4/Pixhawk. The configuration assumes the elevon servos are connected to -- cgit v1.2.3 From 61286451361c0e4547caf2385f56ee6cc8afffb1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 07:37:17 +0200 Subject: mathlib: More C++ fixes --- src/lib/mathlib/math/Matrix.hpp | 2 ++ src/lib/mathlib/math/Vector.hpp | 12 ++++++++---- 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/src/lib/mathlib/math/Matrix.hpp b/src/lib/mathlib/math/Matrix.hpp index c2109b479..ca931e2da 100644 --- a/src/lib/mathlib/math/Matrix.hpp +++ b/src/lib/mathlib/math/Matrix.hpp @@ -77,6 +77,8 @@ public: { } + virtual ~MatrixBase() {}; + /** * copyt ctor */ diff --git a/src/lib/mathlib/math/Vector.hpp b/src/lib/mathlib/math/Vector.hpp index 5017b7c79..0ddf77615 100644 --- a/src/lib/mathlib/math/Vector.hpp +++ b/src/lib/mathlib/math/Vector.hpp @@ -78,19 +78,23 @@ public: } + virtual ~VectorBase() {}; + /** * copy ctor */ - VectorBase(const VectorBase &v) { - arm_col = {N, 1, &data[0]}; + VectorBase(const VectorBase &v) : + arm_col{N, 1, &data[0]} + { memcpy(data, v.data, sizeof(data)); } /** * setting ctor */ - VectorBase(const float d[N]) { - arm_col = {N, 1, &data[0]}; + VectorBase(const float d[N]) : + arm_col{N, 1, &data[0]} + { memcpy(data, d, sizeof(data)); } -- cgit v1.2.3 From e91a4217ad23a0f5190b0e34b7621a5170632a43 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 07:54:12 +0200 Subject: Fix warning --- src/modules/commander/airspeed_calibration.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 598cfe9e2..0e58c68b6 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -186,7 +186,7 @@ int do_airspeed_calibration(int mavlink_fd) usleep(500 * 1000); calibration_counter = 0; - const int maxcount = 3000; + const unsigned maxcount = 3000; /* just take a few samples and make sure pitot tubes are not reversed, timeout after ~30 seconds */ while (calibration_counter < maxcount) { -- cgit v1.2.3 From b0b6ee06448c266dc97d8efbd48be548f4a57ee6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 18:22:38 +0200 Subject: Forbid copy constructor in CDev --- src/drivers/device/device.h | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h index 7df234cab..2d105bb79 100644 --- a/src/drivers/device/device.h +++ b/src/drivers/device/device.h @@ -240,6 +240,7 @@ private: * @param context Pointer to the interrupted context. */ static void dev_interrupt(int irq, void *context); + }; /** @@ -469,6 +470,10 @@ private: * @return OK, or -errno on error. */ int remove_poll_waiter(struct pollfd *fds); + + /* do not allow copying this class */ + CDev(const CDev&); + CDev operator=(const CDev&); }; /** -- cgit v1.2.3 From 1ac2b307e4424d3b6555ab3ca21c43d8de19b81e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 18:23:17 +0200 Subject: Enable stricter compile mode and ensure the most relevant bits are initialized. Needs more work to avoid the remaining warnings --- src/modules/mavlink/mavlink_commands.cpp | 7 +++++-- src/modules/mavlink/mavlink_ftp.cpp | 16 ++++++++++------ src/modules/mavlink/mavlink_main.cpp | 10 +++++++++- src/modules/mavlink/mavlink_main.h | 4 ++++ src/modules/mavlink/mavlink_mission.h | 4 ++++ src/modules/mavlink/mavlink_orb_subscription.h | 4 ++++ src/modules/mavlink/mavlink_receiver.cpp | 12 ++++++------ src/modules/mavlink/mavlink_receiver.h | 4 ++++ src/modules/mavlink/mavlink_stream.h | 4 ++++ src/modules/mavlink/module.mk | 2 ++ 10 files changed, 52 insertions(+), 15 deletions(-) diff --git a/src/modules/mavlink/mavlink_commands.cpp b/src/modules/mavlink/mavlink_commands.cpp index fccd4d9a5..b502c3c86 100644 --- a/src/modules/mavlink/mavlink_commands.cpp +++ b/src/modules/mavlink/mavlink_commands.cpp @@ -40,9 +40,12 @@ #include "mavlink_commands.h" -MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel), _cmd_time(0) +MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : + _cmd_sub(mavlink->add_orb_subscription(ORB_ID(vehicle_command))), + _cmd{}, + _channel(channel), + _cmd_time(0) { - _cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command)); } void diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index 675a6870e..6a2c900af 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -50,16 +50,20 @@ MavlinkFTP::getServer() return _server; } -MavlinkFTP::MavlinkFTP() +MavlinkFTP::MavlinkFTP() : + _session_fds{}, + _workBufs{}, + _workFree{}, + _lock{} { // initialise the request freelist dq_init(&_workFree); sem_init(&_lock, 0, 1); - - // initialize session list - for (size_t i=0; i Date: Tue, 15 Jul 2014 22:08:40 +0200 Subject: Do not initialize variable if value is never read --- src/drivers/hmc5883/hmc5883.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index ad1770300..573b4fbba 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -867,7 +867,8 @@ HMC5883::collect() struct { int16_t x, y, z; } report; - int ret = -EIO; + + int ret; uint8_t cmd; uint8_t check_counter; -- cgit v1.2.3 From 5ef4e08c580a4f15628ed16194a680508ea044bf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 23:14:30 +0200 Subject: hmc5883: Support for three sensors --- src/drivers/hmc5883/hmc5883.cpp | 24 ++++++++++++++++++++---- 1 file changed, 20 insertions(+), 4 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 573b4fbba..26014c6d8 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -162,6 +162,7 @@ private: orb_advert_t _mag_topic; orb_advert_t _subsystem_pub; + orb_id_t _mag_orb_id; perf_counter_t _sample_perf; perf_counter_t _comms_errors; @@ -355,6 +356,7 @@ HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) : _class_instance(-1), _mag_topic(-1), _subsystem_pub(-1), + _mag_orb_id(nullptr), _sample_perf(perf_alloc(PC_ELAPSED, "hmc5883_read")), _comms_errors(perf_alloc(PC_COUNT, "hmc5883_comms_errors")), _buffer_overflows(perf_alloc(PC_COUNT, "hmc5883_buffer_overflows")), @@ -423,6 +425,20 @@ HMC5883::init() _class_instance = register_class_devname(MAG_DEVICE_PATH); + switch (_class_instance) { + case CLASS_DEVICE_PRIMARY: + _mag_orb_id = ORB_ID(sensor_mag0); + break; + + case CLASS_DEVICE_SECONDARY: + _mag_orb_id = ORB_ID(sensor_mag1); + break; + + case CLASS_DEVICE_TERTIARY: + _mag_orb_id = ORB_ID(sensor_mag2); + break; + } + ret = OK; /* sensor is ok, but not calibrated */ _sensor_ok = true; @@ -946,16 +962,16 @@ HMC5883::collect() // apply user specified rotation rotate_3f(_rotation, new_report.x, new_report.y, new_report.z); - if (_class_instance == CLASS_DEVICE_PRIMARY && !(_pub_blocked)) { + if (!(_pub_blocked)) { if (_mag_topic != -1) { /* publish it */ - orb_publish(ORB_ID(sensor_mag0), _mag_topic, &new_report); + orb_publish(_mag_orb_id, _mag_topic, &new_report); } else { - _mag_topic = orb_advertise(ORB_ID(sensor_mag0), &new_report); + _mag_topic = orb_advertise(_mag_orb_id, &new_report); if (_mag_topic < 0) - debug("failed to create sensor_mag publication"); + debug("ADVERT FAIL"); } } -- cgit v1.2.3 From 32ed1eae80f4004daa63b4331a66b774becf651f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 23:14:50 +0200 Subject: mpu6000: Support for up to three accels / gyros --- src/drivers/mpu6000/mpu6000.cpp | 48 ++++++++++++++++++++--------------------- 1 file changed, 24 insertions(+), 24 deletions(-) diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 25fd7d8a8..09eec0caf 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -215,6 +215,7 @@ private: float _accel_range_scale; float _accel_range_m_s2; orb_advert_t _accel_topic; + orb_id_t _accel_orb_id; int _accel_class_instance; RingBuffer *_gyro_reports; @@ -367,6 +368,7 @@ protected: private: MPU6000 *_parent; orb_advert_t _gyro_topic; + orb_id_t _gyro_orb_id; int _gyro_class_instance; }; @@ -383,6 +385,7 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), _accel_topic(-1), + _accel_orb_id(nullptr), _accel_class_instance(-1), _gyro_reports(nullptr), _gyro_range_scale(0.0f), @@ -505,17 +508,23 @@ MPU6000::init() /* measurement will have generated a report, publish */ switch (_accel_class_instance) { case CLASS_DEVICE_PRIMARY: - _accel_topic = orb_advertise(ORB_ID(sensor_accel0), &arp); + _accel_orb_id = ORB_ID(sensor_accel0); break; case CLASS_DEVICE_SECONDARY: - _accel_topic = orb_advertise(ORB_ID(sensor_accel1), &arp); + _accel_orb_id = ORB_ID(sensor_accel1); + break; + + case CLASS_DEVICE_TERTIARY: + _accel_orb_id = ORB_ID(sensor_accel2); break; } + _accel_topic = orb_advertise(_accel_orb_id, &arp); + if (_accel_topic < 0) { - warnx("failed to create sensor_accel publication"); + warnx("ADVERT FAIL"); } @@ -525,17 +534,23 @@ MPU6000::init() switch (_gyro->_gyro_class_instance) { case CLASS_DEVICE_PRIMARY: - _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro0), &grp); + _gyro->_gyro_orb_id = ORB_ID(sensor_gyro0); break; case CLASS_DEVICE_SECONDARY: - _gyro->_gyro_topic = orb_advertise(ORB_ID(sensor_gyro1), &grp); + _gyro->_gyro_orb_id = ORB_ID(sensor_gyro1); + break; + + case CLASS_DEVICE_TERTIARY: + _gyro->_gyro_orb_id = ORB_ID(sensor_gyro2); break; } + _gyro->_gyro_topic = orb_advertise(_gyro->_gyro_orb_id, &grp); + if (_gyro->_gyro_topic < 0) { - warnx("failed to create sensor_gyro publication"); + warnx("ADVERT FAIL"); } out: @@ -1360,28 +1375,12 @@ MPU6000::measure() if (!(_pub_blocked)) { /* publish it */ - switch (_accel_class_instance) { - case CLASS_DEVICE_PRIMARY: - orb_publish(ORB_ID(sensor_accel0), _accel_topic, &arb); - break; - - case CLASS_DEVICE_SECONDARY: - orb_publish(ORB_ID(sensor_accel1), _accel_topic, &arb); - break; - } + orb_publish(_accel_orb_id, _accel_topic, &arb); } if (!(_pub_blocked)) { /* publish it */ - switch (_gyro->_gyro_class_instance) { - case CLASS_DEVICE_PRIMARY: - orb_publish(ORB_ID(sensor_gyro0), _gyro->_gyro_topic, &grb); - break; - - case CLASS_DEVICE_SECONDARY: - orb_publish(ORB_ID(sensor_gyro1), _gyro->_gyro_topic, &grb); - break; - } + orb_publish(_gyro->_gyro_orb_id, _gyro->_gyro_topic, &grb); } /* stop measuring */ @@ -1402,6 +1401,7 @@ MPU6000_gyro::MPU6000_gyro(MPU6000 *parent, const char *path) : CDev("MPU6000_gyro", path), _parent(parent), _gyro_topic(-1), + _gyro_orb_id(nullptr), _gyro_class_instance(-1) { } -- cgit v1.2.3 From 65367f7a99907fbd6a204ba44ee443816c635482 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 23:16:04 +0200 Subject: L3GD20: Support for up to three gyros --- src/drivers/l3gd20/l3gd20.cpp | 33 ++++++++++++++++++--------------- 1 file changed, 18 insertions(+), 15 deletions(-) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 9e5eb00db..5e90733ff 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -213,6 +213,7 @@ private: float _gyro_range_scale; float _gyro_range_rad_s; orb_advert_t _gyro_topic; + orb_id_t _orb_id; int _class_instance; unsigned _current_rate; @@ -339,6 +340,7 @@ L3GD20::L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotati _gyro_range_scale(0.0f), _gyro_range_rad_s(0.0f), _gyro_topic(-1), + _orb_id(nullptr), _class_instance(-1), _current_rate(0), _orientation(SENSOR_BOARD_ROTATION_DEFAULT), @@ -399,6 +401,20 @@ L3GD20::init() _class_instance = register_class_devname(GYRO_DEVICE_PATH); + switch (_class_instance) { + case CLASS_DEVICE_PRIMARY: + _orb_id = ORB_ID(sensor_gyro0); + break; + + case CLASS_DEVICE_SECONDARY: + _orb_id = ORB_ID(sensor_gyro1); + break; + + case CLASS_DEVICE_TERTIARY: + _orb_id = ORB_ID(sensor_gyro2); + break; + } + reset(); measure(); @@ -407,12 +423,7 @@ L3GD20::init() struct gyro_report grp; _reports->get(&grp); - if (_class_instance == CLASS_DEVICE_PRIMARY) { - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro0), &grp); - - } else if (_class_instance == CLASS_DEVICE_SECONDARY) { - _gyro_topic = orb_advertise(ORB_ID(sensor_gyro1), &grp); - } + _gyro_topic = orb_advertise(_orb_id, &grp); if (_gyro_topic < 0) { debug("failed to create sensor_gyro publication"); @@ -935,15 +946,7 @@ L3GD20::measure() /* publish for subscribers */ if (!(_pub_blocked)) { /* publish it */ - switch (_class_instance) { - case CLASS_DEVICE_PRIMARY: - orb_publish(ORB_ID(sensor_gyro0), _gyro_topic, &report); - break; - - case CLASS_DEVICE_SECONDARY: - orb_publish(ORB_ID(sensor_gyro1), _gyro_topic, &report); - break; - } + orb_publish(_orb_id, _gyro_topic, &report); } _read++; -- cgit v1.2.3 From 64e33b8896d717f73a1b1ad3189b97c98c9bddfd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 23:18:04 +0200 Subject: uORB: Support up to three topics per sensor --- src/modules/uORB/objects_common.cpp | 3 +++ src/modules/uORB/topics/sensor_combined.h | 24 ++++++++++++++++++++++++ 2 files changed, 27 insertions(+) diff --git a/src/modules/uORB/objects_common.cpp b/src/modules/uORB/objects_common.cpp index 679d6ea4f..08c3ce1ac 100644 --- a/src/modules/uORB/objects_common.cpp +++ b/src/modules/uORB/objects_common.cpp @@ -48,14 +48,17 @@ #include ORB_DEFINE(sensor_mag0, struct mag_report); ORB_DEFINE(sensor_mag1, struct mag_report); +ORB_DEFINE(sensor_mag2, struct mag_report); #include ORB_DEFINE(sensor_accel0, struct accel_report); ORB_DEFINE(sensor_accel1, struct accel_report); +ORB_DEFINE(sensor_accel2, struct accel_report); #include ORB_DEFINE(sensor_gyro0, struct gyro_report); ORB_DEFINE(sensor_gyro1, struct gyro_report); +ORB_DEFINE(sensor_gyro2, struct gyro_report); #include ORB_DEFINE(sensor_baro0, struct baro_report); diff --git a/src/modules/uORB/topics/sensor_combined.h b/src/modules/uORB/topics/sensor_combined.h index fa3367de9..06dfcdab3 100644 --- a/src/modules/uORB/topics/sensor_combined.h +++ b/src/modules/uORB/topics/sensor_combined.h @@ -95,6 +95,30 @@ struct sensor_combined_s { float magnetometer_cuttoff_freq_hz; /**< Internal analog low pass frequency of sensor */ uint64_t magnetometer_timestamp; /**< Magnetometer timestamp */ + int16_t gyro1_raw[3]; /**< Raw sensor values of angular velocity */ + float gyro1_rad_s[3]; /**< Angular velocity in radian per seconds */ + uint64_t gyro1_timestamp; /**< Gyro timestamp */ + + int16_t accelerometer1_raw[3]; /**< Raw acceleration in NED body frame */ + float accelerometer1_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */ + uint64_t accelerometer1_timestamp; /**< Accelerometer timestamp */ + + int16_t magnetometer1_raw[3]; /**< Raw magnetic field in NED body frame */ + float magnetometer1_ga[3]; /**< Magnetic field in NED body frame, in Gauss */ + uint64_t magnetometer1_timestamp; /**< Magnetometer timestamp */ + + int16_t gyro2_raw[3]; /**< Raw sensor values of angular velocity */ + float gyro2_rad_s[3]; /**< Angular velocity in radian per seconds */ + uint64_t gyro2_timestamp; /**< Gyro timestamp */ + + int16_t accelerometer2_raw[3]; /**< Raw acceleration in NED body frame */ + float accelerometer2_m_s2[3]; /**< Acceleration in NED body frame, in m/s^2 */ + uint64_t accelerometer2_timestamp; /**< Accelerometer timestamp */ + + int16_t magnetometer2_raw[3]; /**< Raw magnetic field in NED body frame */ + float magnetometer2_ga[3]; /**< Magnetic field in NED body frame, in Gauss */ + uint64_t magnetometer2_timestamp; /**< Magnetometer timestamp */ + float baro_pres_mbar; /**< Barometric pressure, already temp. comp. */ float baro_alt_meter; /**< Altitude, already temp. comp. */ float baro_temp_celcius; /**< Temperature in degrees celsius */ -- cgit v1.2.3 From b8b6974e22b7292d5251f1d2c49b2c81e09cc06b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 23:19:45 +0200 Subject: sdlog2: Add support for up to three IMU sensors --- src/modules/sdlog2/sdlog2.c | 66 ++++++++++++++++++++++++++++++++++++ src/modules/sdlog2/sdlog2_messages.h | 10 ++++-- 2 files changed, 73 insertions(+), 3 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 0d36fa2c6..f534c0f4c 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -1073,6 +1073,12 @@ int sdlog2_thread_main(int argc, char *argv[]) hrt_abstime magnetometer_timestamp = 0; hrt_abstime barometer_timestamp = 0; hrt_abstime differential_pressure_timestamp = 0; + hrt_abstime gyro1_timestamp = 0; + hrt_abstime accelerometer1_timestamp = 0; + hrt_abstime magnetometer1_timestamp = 0; + hrt_abstime gyro2_timestamp = 0; + hrt_abstime accelerometer2_timestamp = 0; + hrt_abstime magnetometer2_timestamp = 0; /* initialize calculated mean SNR */ float snr_mean = 0.0f; @@ -1209,6 +1215,8 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- SENSOR COMBINED --- */ if (copy_if_updated(ORB_ID(sensor_combined), subs.sensor_sub, &buf.sensor)) { bool write_IMU = false; + bool write_IMU1 = false; + bool write_IMU2 = false; bool write_SENS = false; if (buf.sensor.timestamp != gyro_timestamp) { @@ -1260,6 +1268,64 @@ int sdlog2_thread_main(int argc, char *argv[]) LOGBUFFER_WRITE_AND_COUNT(SENS); } + if (buf.sensor.accelerometer1_timestamp != accelerometer1_timestamp) { + accelerometer1_timestamp = buf.sensor.accelerometer1_timestamp; + write_IMU1 = true; + } + + if (buf.sensor.gyro1_timestamp != gyro1_timestamp) { + gyro1_timestamp = buf.sensor.gyro1_timestamp; + write_IMU1 = true; + } + + if (buf.sensor.magnetometer1_timestamp != magnetometer1_timestamp) { + magnetometer1_timestamp = buf.sensor.magnetometer1_timestamp; + write_IMU1 = true; + } + + if (write_IMU1) { + log_msg.msg_type = LOG_IMU1_MSG; + log_msg.body.log_IMU.gyro_x = buf.sensor.gyro1_rad_s[0]; + log_msg.body.log_IMU.gyro_y = buf.sensor.gyro1_rad_s[1]; + log_msg.body.log_IMU.gyro_z = buf.sensor.gyro1_rad_s[2]; + log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer1_m_s2[0]; + log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer1_m_s2[1]; + log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer1_m_s2[2]; + log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer1_ga[0]; + log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer1_ga[1]; + log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer1_ga[2]; + LOGBUFFER_WRITE_AND_COUNT(IMU); + } + + if (buf.sensor.accelerometer2_timestamp != accelerometer2_timestamp) { + accelerometer2_timestamp = buf.sensor.accelerometer2_timestamp; + write_IMU2 = true; + } + + if (buf.sensor.gyro2_timestamp != gyro2_timestamp) { + gyro2_timestamp = buf.sensor.gyro2_timestamp; + write_IMU2 = true; + } + + if (buf.sensor.magnetometer2_timestamp != magnetometer2_timestamp) { + magnetometer2_timestamp = buf.sensor.magnetometer2_timestamp; + write_IMU2 = true; + } + + if (write_IMU2) { + log_msg.msg_type = LOG_IMU2_MSG; + log_msg.body.log_IMU.gyro_x = buf.sensor.gyro2_rad_s[0]; + log_msg.body.log_IMU.gyro_y = buf.sensor.gyro2_rad_s[1]; + log_msg.body.log_IMU.gyro_z = buf.sensor.gyro2_rad_s[2]; + log_msg.body.log_IMU.acc_x = buf.sensor.accelerometer2_m_s2[0]; + log_msg.body.log_IMU.acc_y = buf.sensor.accelerometer2_m_s2[1]; + log_msg.body.log_IMU.acc_z = buf.sensor.accelerometer2_m_s2[2]; + log_msg.body.log_IMU.mag_x = buf.sensor.magnetometer2_ga[0]; + log_msg.body.log_IMU.mag_y = buf.sensor.magnetometer2_ga[1]; + log_msg.body.log_IMU.mag_z = buf.sensor.magnetometer2_ga[2]; + LOGBUFFER_WRITE_AND_COUNT(IMU); + } + } /* --- ATTITUDE --- */ diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 87f7f718f..b14ef04cc 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -73,6 +73,8 @@ struct log_ATSP_s { /* --- IMU - IMU SENSORS --- */ #define LOG_IMU_MSG 4 +#define LOG_IMU1_MSG 22 +#define LOG_IMU2_MSG 23 struct log_IMU_s { float acc_x; float acc_y; @@ -276,8 +278,8 @@ struct log_DIST_s { uint8_t flags; }; -// ID 22 available -// ID 23 available +/* LOG IMU1 and IMU2 MSGs consume IDs 22 and 23 */ + /* --- PWR - ONBOARD POWER SYSTEM --- */ #define LOG_PWR_MSG 24 @@ -420,7 +422,9 @@ static const struct log_format_s log_formats[] = { /* business-level messages, ID < 0x80 */ LOG_FORMAT(ATT, "fffffffff", "Roll,Pitch,Yaw,RollRate,PitchRate,YawRate,GX,GY,GZ"), LOG_FORMAT(ATSP, "ffff", "RollSP,PitchSP,YawSP,ThrustSP"), - LOG_FORMAT(IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), + LOG_FORMAT_S(IMU, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), + LOG_FORMAT_S(IMU1, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), + LOG_FORMAT_S(IMU2, IMU, "fffffffff", "AccX,AccY,AccZ,GyroX,GyroY,GyroZ,MagX,MagY,MagZ"), LOG_FORMAT(SENS, "fffff", "BaroPres,BaroAlt,BaroTemp,DiffPres,DiffPresFilt"), LOG_FORMAT(LPOS, "ffffffffLLfBBBff", "X,Y,Z,Dist,DistR,VX,VY,VZ,RLat,RLon,RAlt,PFlg,LFlg,GFlg,EPH,EPV"), LOG_FORMAT(LPSP, "ffff", "X,Y,Z,Yaw"), -- cgit v1.2.3 From 9e97994ef92d3ef3496384c4b11c734138c5f3a3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 23:20:02 +0200 Subject: drivers: Up to three units support --- src/drivers/device/device.h | 3 ++- src/drivers/drv_accel.h | 1 + src/drivers/drv_gyro.h | 1 + src/drivers/drv_mag.h | 2 +- 4 files changed, 5 insertions(+), 2 deletions(-) diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h index b65649d9d..813e1542b 100644 --- a/src/drivers/device/device.h +++ b/src/drivers/device/device.h @@ -540,7 +540,8 @@ private: // class instance for primary driver of each class enum CLASS_DEVICE { CLASS_DEVICE_PRIMARY=0, - CLASS_DEVICE_SECONDARY=1 + CLASS_DEVICE_SECONDARY=1, + CLASS_DEVICE_TERTIARY=2 }; #endif /* _DEVICE_DEVICE_H */ diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h index a6abaec70..1f98d966b 100644 --- a/src/drivers/drv_accel.h +++ b/src/drivers/drv_accel.h @@ -83,6 +83,7 @@ struct accel_scale { */ ORB_DECLARE(sensor_accel0); ORB_DECLARE(sensor_accel1); +ORB_DECLARE(sensor_accel2); /* * ioctl() definitions diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h index 3635cbce1..41b013a44 100644 --- a/src/drivers/drv_gyro.h +++ b/src/drivers/drv_gyro.h @@ -83,6 +83,7 @@ struct gyro_scale { */ ORB_DECLARE(sensor_gyro0); ORB_DECLARE(sensor_gyro1); +ORB_DECLARE(sensor_gyro2); /* * ioctl() definitions diff --git a/src/drivers/drv_mag.h b/src/drivers/drv_mag.h index a6c509d31..5ddf5d08e 100644 --- a/src/drivers/drv_mag.h +++ b/src/drivers/drv_mag.h @@ -81,7 +81,7 @@ struct mag_scale { */ ORB_DECLARE(sensor_mag0); ORB_DECLARE(sensor_mag1); - +ORB_DECLARE(sensor_mag2); /* * mag device types, for _device_id -- cgit v1.2.3 From c467d1635efda46bc7200b95741381fc98e161ae Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 23:21:00 +0200 Subject: Build fixes for example --- src/examples/matlab_csv_serial/matlab_csv_serial.c | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/examples/matlab_csv_serial/matlab_csv_serial.c b/src/examples/matlab_csv_serial/matlab_csv_serial.c index 1327d1a23..c66bebeec 100644 --- a/src/examples/matlab_csv_serial/matlab_csv_serial.c +++ b/src/examples/matlab_csv_serial/matlab_csv_serial.c @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (C) 2014 PX4 Development Team. All rights reserved. + * Copyright (c) 2014 PX4 Development Team. All rights reserved. * * Redistribution and use in source and binary forms, with or without * modification, are permitted provided that the following conditions @@ -60,6 +60,7 @@ #include #include #include +#include #include __EXPORT int matlab_csv_serial_main(int argc, char *argv[]); @@ -153,7 +154,6 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) /* Try to set baud rate */ struct termios uart_config; int termios_state; - bool is_usb = false; /* Back up the original uart configuration to restore it after exit */ if ((termios_state = tcgetattr(serial_fd, &uart_config)) < 0) { @@ -225,7 +225,7 @@ int matlab_csv_serial_thread_main(int argc, char *argv[]) if (fds[0].revents & POLLIN) { orb_copy(ORB_ID(sensor_accel0), accel0_sub, &accel0); - orb_copy(ORB_ID(sensor_accel1), accel0_sub, &accel1); + orb_copy(ORB_ID(sensor_accel1), accel1_sub, &accel1); orb_copy(ORB_ID(sensor_gyro0), gyro0_sub, &gyro0); orb_copy(ORB_ID(sensor_gyro1), gyro1_sub, &gyro1); -- cgit v1.2.3 From b6bac2c88d44fcb7ee0b1fd579f0f0fcc19c2410 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 23:22:04 +0200 Subject: sensors: Support for up to three sensors of the IMU types --- src/modules/sensors/sensors.cpp | 110 ++++++++++++++++++++++++++++++++++++++-- 1 file changed, 107 insertions(+), 3 deletions(-) diff --git a/src/modules/sensors/sensors.cpp b/src/modules/sensors/sensors.cpp index 388cd2dcc..4e8a8c01d 100644 --- a/src/modules/sensors/sensors.cpp +++ b/src/modules/sensors/sensors.cpp @@ -199,9 +199,15 @@ private: bool _hil_enabled; /**< if true, HIL is active */ bool _publishing; /**< if true, we are publishing sensor data */ - int _gyro_sub; /**< raw gyro data subscription */ - int _accel_sub; /**< raw accel data subscription */ - int _mag_sub; /**< raw mag data subscription */ + int _gyro_sub; /**< raw gyro0 data subscription */ + int _accel_sub; /**< raw accel0 data subscription */ + int _mag_sub; /**< raw mag0 data subscription */ + int _gyro1_sub; /**< raw gyro1 data subscription */ + int _accel1_sub; /**< raw accel1 data subscription */ + int _mag1_sub; /**< raw mag1 data subscription */ + int _gyro2_sub; /**< raw gyro2 data subscription */ + int _accel2_sub; /**< raw accel2 data subscription */ + int _mag2_sub; /**< raw mag2 data subscription */ int _rc_sub; /**< raw rc channels data subscription */ int _baro_sub; /**< raw baro data subscription */ int _airspeed_sub; /**< airspeed subscription */ @@ -478,6 +484,12 @@ Sensors::Sensors() : _gyro_sub(-1), _accel_sub(-1), _mag_sub(-1), + _gyro1_sub(-1), + _accel1_sub(-1), + _mag1_sub(-1), + _gyro2_sub(-1), + _accel2_sub(-1), + _mag2_sub(-1), _rc_sub(-1), _baro_sub(-1), _vcontrol_mode_sub(-1), @@ -1019,6 +1031,48 @@ Sensors::accel_poll(struct sensor_combined_s &raw) raw.accelerometer_timestamp = accel_report.timestamp; } + + orb_check(_accel1_sub, &accel_updated); + + if (accel_updated) { + struct accel_report accel_report; + + orb_copy(ORB_ID(sensor_accel1), _accel_sub, &accel_report); + + math::Vector<3> vect(accel_report.x, accel_report.y, accel_report.z); + vect = _board_rotation * vect; + + raw.accelerometer1_m_s2[0] = vect(0); + raw.accelerometer1_m_s2[1] = vect(1); + raw.accelerometer1_m_s2[2] = vect(2); + + raw.accelerometer1_raw[0] = accel_report.x_raw; + raw.accelerometer1_raw[1] = accel_report.y_raw; + raw.accelerometer1_raw[2] = accel_report.z_raw; + + raw.accelerometer1_timestamp = accel_report.timestamp; + } + + orb_check(_accel2_sub, &accel_updated); + + if (accel_updated) { + struct accel_report accel_report; + + orb_copy(ORB_ID(sensor_accel2), _accel_sub, &accel_report); + + math::Vector<3> vect(accel_report.x, accel_report.y, accel_report.z); + vect = _board_rotation * vect; + + raw.accelerometer2_m_s2[0] = vect(0); + raw.accelerometer2_m_s2[1] = vect(1); + raw.accelerometer2_m_s2[2] = vect(2); + + raw.accelerometer2_raw[0] = accel_report.x_raw; + raw.accelerometer2_raw[1] = accel_report.y_raw; + raw.accelerometer2_raw[2] = accel_report.z_raw; + + raw.accelerometer2_timestamp = accel_report.timestamp; + } } void @@ -1045,6 +1099,48 @@ Sensors::gyro_poll(struct sensor_combined_s &raw) raw.timestamp = gyro_report.timestamp; } + + orb_check(_gyro1_sub, &gyro_updated); + + if (gyro_updated) { + struct gyro_report gyro_report; + + orb_copy(ORB_ID(sensor_gyro1), _gyro1_sub, &gyro_report); + + math::Vector<3> vect(gyro_report.x, gyro_report.y, gyro_report.z); + vect = _board_rotation * vect; + + raw.gyro1_rad_s[0] = vect(0); + raw.gyro1_rad_s[1] = vect(1); + raw.gyro1_rad_s[2] = vect(2); + + raw.gyro1_raw[0] = gyro_report.x_raw; + raw.gyro1_raw[1] = gyro_report.y_raw; + raw.gyro1_raw[2] = gyro_report.z_raw; + + raw.gyro1_timestamp = gyro_report.timestamp; + } + + orb_check(_gyro2_sub, &gyro_updated); + + if (gyro_updated) { + struct gyro_report gyro_report; + + orb_copy(ORB_ID(sensor_gyro2), _gyro_sub, &gyro_report); + + math::Vector<3> vect(gyro_report.x, gyro_report.y, gyro_report.z); + vect = _board_rotation * vect; + + raw.gyro2_rad_s[0] = vect(0); + raw.gyro2_rad_s[1] = vect(1); + raw.gyro2_rad_s[2] = vect(2); + + raw.gyro2_raw[0] = gyro_report.x_raw; + raw.gyro2_raw[1] = gyro_report.y_raw; + raw.gyro2_raw[2] = gyro_report.z_raw; + + raw.gyro2_timestamp = gyro_report.timestamp; + } } void @@ -1060,6 +1156,8 @@ Sensors::mag_poll(struct sensor_combined_s &raw) math::Vector<3> vect(mag_report.x, mag_report.y, mag_report.z); + // XXX we need device-id based handling here + if (_mag_is_external) { vect = _external_mag_rotation * vect; @@ -1621,6 +1719,12 @@ Sensors::task_main() _gyro_sub = orb_subscribe(ORB_ID(sensor_gyro0)); _accel_sub = orb_subscribe(ORB_ID(sensor_accel0)); _mag_sub = orb_subscribe(ORB_ID(sensor_mag0)); + _gyro1_sub = orb_subscribe(ORB_ID(sensor_gyro1)); + _accel1_sub = orb_subscribe(ORB_ID(sensor_accel1)); + _mag1_sub = orb_subscribe(ORB_ID(sensor_mag1)); + _gyro2_sub = orb_subscribe(ORB_ID(sensor_gyro2)); + _accel2_sub = orb_subscribe(ORB_ID(sensor_accel2)); + _mag2_sub = orb_subscribe(ORB_ID(sensor_mag2)); _rc_sub = orb_subscribe(ORB_ID(input_rc)); _baro_sub = orb_subscribe(ORB_ID(sensor_baro0)); _diff_pres_sub = orb_subscribe(ORB_ID(differential_pressure)); -- cgit v1.2.3 From 43bc2c3ef2a867a015e7198c797d089d6252fdde Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 15 Jul 2014 23:32:03 +0200 Subject: LSM303D: Support for tertiary sensors --- src/drivers/lsm303d/lsm303d.cpp | 47 ++++++++++++++++++++--------------------- 1 file changed, 23 insertions(+), 24 deletions(-) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index ff0eda60b..2750f8755 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -284,6 +284,7 @@ private: unsigned _mag_samplerate; orb_advert_t _accel_topic; + orb_id_t _accel_orb_id; int _accel_class_instance; unsigned _accel_read; @@ -485,6 +486,7 @@ private: LSM303D *_parent; orb_advert_t _mag_topic; + orb_id_t _mag_orb_id; int _mag_class_instance; void measure(); @@ -508,6 +510,7 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota _mag_range_scale(0.0f), _mag_samplerate(0), _accel_topic(-1), + _accel_orb_id(nullptr), _accel_class_instance(-1), _accel_read(0), _mag_read(0), @@ -618,16 +621,22 @@ LSM303D::init() /* measurement will have generated a report, publish */ switch (_mag->_mag_class_instance) { case CLASS_DEVICE_PRIMARY: - _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag0), &mrp); + _mag->_mag_orb_id = ORB_ID(sensor_mag0); break; case CLASS_DEVICE_SECONDARY: - _mag->_mag_topic = orb_advertise(ORB_ID(sensor_mag1), &mrp); + _mag->_mag_orb_id = ORB_ID(sensor_mag1); + break; + + case CLASS_DEVICE_TERTIARY: + _mag->_mag_orb_id = ORB_ID(sensor_mag2); break; } + _mag->_mag_topic = orb_advertise(_mag->_mag_orb_id, &mrp); + if (_mag->_mag_topic < 0) { - warnx("failed to create sensor_mag publication"); + warnx("ADVERT ERR"); } _accel_class_instance = register_class_devname(ACCEL_DEVICE_PATH); @@ -639,17 +648,22 @@ LSM303D::init() /* measurement will have generated a report, publish */ switch (_accel_class_instance) { case CLASS_DEVICE_PRIMARY: - _accel_topic = orb_advertise(ORB_ID(sensor_accel0), &arp); + _accel_orb_id = ORB_ID(sensor_accel0); break; case CLASS_DEVICE_SECONDARY: - _accel_topic = orb_advertise(ORB_ID(sensor_accel1), &arp); + _accel_orb_id = ORB_ID(sensor_accel1); break; + case CLASS_DEVICE_TERTIARY: + _accel_orb_id = ORB_ID(sensor_accel2); + break; } + _accel_topic = orb_advertise(_accel_orb_id, &arp); + if (_accel_topic < 0) { - warnx("failed to create sensor_accel publication"); + warnx("ADVERT ERR"); } out: @@ -1570,15 +1584,7 @@ LSM303D::measure() if (!(_pub_blocked)) { /* publish it */ - switch (_accel_class_instance) { - case CLASS_DEVICE_PRIMARY: - orb_publish(ORB_ID(sensor_accel0), _accel_topic, &accel_report); - break; - - case CLASS_DEVICE_SECONDARY: - orb_publish(ORB_ID(sensor_accel1), _accel_topic, &accel_report); - break; - } + orb_publish(_accel_orb_id, _accel_topic, &accel_report); } _accel_read++; @@ -1655,15 +1661,7 @@ LSM303D::mag_measure() if (!(_pub_blocked)) { /* publish it */ - switch (_mag->_mag_class_instance) { - case CLASS_DEVICE_PRIMARY: - orb_publish(ORB_ID(sensor_mag0), _mag->_mag_topic, &mag_report); - break; - - case CLASS_DEVICE_SECONDARY: - orb_publish(ORB_ID(sensor_mag1), _mag->_mag_topic, &mag_report); - break; - } + orb_publish(_mag->_mag_orb_id, _mag->_mag_topic, &mag_report); } _mag_read++; @@ -1757,6 +1755,7 @@ LSM303D_mag::LSM303D_mag(LSM303D *parent) : CDev("LSM303D_mag", LSM303D_DEVICE_PATH_MAG), _parent(parent), _mag_topic(-1), + _mag_orb_id(nullptr), _mag_class_instance(-1) { } -- cgit v1.2.3 From f89573a6ed6e43c9e5935b92929b6082089226c9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 07:51:24 +0200 Subject: HMC5883 driver: stack size adjustments of start handler and start return review / comments --- src/drivers/hmc5883/hmc5883.cpp | 9 ++++++--- src/drivers/hmc5883/module.mk | 5 ++--- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 4aef43102..0cde1045c 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -867,7 +867,7 @@ HMC5883::collect() struct { int16_t x, y, z; } report; - int ret = -EIO; + int ret; uint8_t cmd; uint8_t check_counter; @@ -1157,7 +1157,7 @@ int HMC5883::calibrate(struct file *filp, unsigned enable) out: if (OK != ioctl(filp, MAGIOCSSCALE, (long unsigned int)&mscale_previous)) { - warn("WARNING: failed to set new scale / offsets for mag"); + warn("failed to set new scale / offsets for mag"); } /* set back to normal mode */ @@ -1353,6 +1353,9 @@ void usage(); /** * Start the driver. + * + * This function call only returns once the driver + * is either successfully up and running or failed to start. */ void start(int bus, enum Rotation rotation) @@ -1443,7 +1446,7 @@ test(int bus) int fd = open(path, O_RDONLY); if (fd < 0) - err(1, "%s open failed (try 'hmc5883 start' if the driver is not running", path); + err(1, "%s open failed (try 'hmc5883 start')", path); /* do a simple demand read */ sz = read(fd, &report, sizeof(report)); diff --git a/src/drivers/hmc5883/module.mk b/src/drivers/hmc5883/module.mk index 07377556d..f51a2b580 100644 --- a/src/drivers/hmc5883/module.mk +++ b/src/drivers/hmc5883/module.mk @@ -37,7 +37,6 @@ MODULE_COMMAND = hmc5883 -# XXX seems excessive, check if 2048 is sufficient -MODULE_STACKSIZE = 4096 - SRCS = hmc5883.cpp + +MODULE_STACKSIZE = 1200 -- cgit v1.2.3 From c2f97e628cf060d35db22526b450b919f0c6cf59 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 07:51:47 +0200 Subject: L3GD20 driver: stack size adjustments of start handler and start return review / comments --- src/drivers/l3gd20/l3gd20.cpp | 3 +++ src/drivers/l3gd20/module.mk | 2 ++ 2 files changed, 5 insertions(+) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 64d1a7e55..2273f8aec 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -990,6 +990,9 @@ void info(); /** * Start the driver. + * + * This function call only returns once the driver + * started or failed to detect the sensor. */ void start(bool external_bus, enum Rotation rotation) diff --git a/src/drivers/l3gd20/module.mk b/src/drivers/l3gd20/module.mk index 23e77e871..83752e08b 100644 --- a/src/drivers/l3gd20/module.mk +++ b/src/drivers/l3gd20/module.mk @@ -4,3 +4,5 @@ MODULE_COMMAND = l3gd20 SRCS = l3gd20.cpp + +MODULE_STACKSIZE = 1200 -- cgit v1.2.3 From fa6f69581ed7dca03ca6ee2cfb8565343400f419 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 07:52:18 +0200 Subject: LSM303D: start handler fix and start routine review --- src/drivers/lsm303d/lsm303d.cpp | 3 +++ src/drivers/lsm303d/module.mk | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index 45e775055..d70bff69a 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -1803,6 +1803,9 @@ void usage(); /** * Start the driver. + * + * This function call only returns once the driver is + * up and running or failed to detect the sensor. */ void start(bool external_bus, enum Rotation rotation) diff --git a/src/drivers/lsm303d/module.mk b/src/drivers/lsm303d/module.mk index e40f718c5..6e9c22799 100644 --- a/src/drivers/lsm303d/module.mk +++ b/src/drivers/lsm303d/module.mk @@ -5,4 +5,4 @@ MODULE_COMMAND = lsm303d SRCS = lsm303d.cpp - +MODULE_STACKSIZE = 1200 -- cgit v1.2.3 From 91bedc5c1c84fa79945f32462dbe3fe30c0ff5e4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 07:54:09 +0200 Subject: airspeed drivers: Start handlers stack fixes and start handler review --- src/drivers/ets_airspeed/ets_airspeed.cpp | 3 +++ src/drivers/ets_airspeed/module.mk | 3 ++- src/drivers/meas_airspeed/meas_airspeed.cpp | 3 +++ src/drivers/meas_airspeed/module.mk | 3 ++- 4 files changed, 10 insertions(+), 2 deletions(-) diff --git a/src/drivers/ets_airspeed/ets_airspeed.cpp b/src/drivers/ets_airspeed/ets_airspeed.cpp index c15a0cee4..f98d615a2 100644 --- a/src/drivers/ets_airspeed/ets_airspeed.cpp +++ b/src/drivers/ets_airspeed/ets_airspeed.cpp @@ -286,6 +286,9 @@ void info(); /** * Start the driver. + * + * This function only returns if the sensor is up and running + * or could not be detected successfully. */ void start(int i2c_bus) diff --git a/src/drivers/ets_airspeed/module.mk b/src/drivers/ets_airspeed/module.mk index 15346c5c5..966a5b819 100644 --- a/src/drivers/ets_airspeed/module.mk +++ b/src/drivers/ets_airspeed/module.mk @@ -36,6 +36,7 @@ # MODULE_COMMAND = ets_airspeed -MODULE_STACKSIZE = 2048 SRCS = ets_airspeed.cpp + +MODULE_STACKSIZE = 1200 diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 07611f903..d643fcad6 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -420,6 +420,9 @@ void info(); /** * Start the driver. + * + * This function call only returns once the driver is up and running + * or failed to detect the sensor. */ void start(int i2c_bus) diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk index fed4078b6..84192d1b5 100644 --- a/src/drivers/meas_airspeed/module.mk +++ b/src/drivers/meas_airspeed/module.mk @@ -36,6 +36,7 @@ # MODULE_COMMAND = meas_airspeed -MODULE_STACKSIZE = 2048 SRCS = meas_airspeed.cpp + +MODULE_STACKSIZE = 1200 -- cgit v1.2.3 From 5b38b5e37170ffb079ef228f117f7e8b594353c8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 07:55:53 +0200 Subject: MPU6K: Start handler startup and stack review and adjustments --- src/drivers/mpu6000/module.mk | 5 ++--- src/drivers/mpu6000/mpu6000.cpp | 5 ++++- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/src/drivers/mpu6000/module.mk b/src/drivers/mpu6000/module.mk index c7d9cd3ef..6087e1509 100644 --- a/src/drivers/mpu6000/module.mk +++ b/src/drivers/mpu6000/module.mk @@ -37,7 +37,6 @@ MODULE_COMMAND = mpu6000 -# XXX seems excessive, check if 2048 is not sufficient -MODULE_STACKSIZE = 4096 - SRCS = mpu6000.cpp + +MODULE_STACKSIZE = 1200 diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 1b3a96a0d..442f0a37c 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -1437,6 +1437,9 @@ void usage(); /** * Start the driver. + * + * This function only returns if the driver is up and running + * or failed to detect the sensor. */ void start(bool external_bus, enum Rotation rotation) @@ -1507,7 +1510,7 @@ test(bool external_bus) int fd = open(path_accel, O_RDONLY); if (fd < 0) - err(1, "%s open failed (try 'mpu6000 start' if the driver is not running)", + err(1, "%s open failed (try 'mpu6000 start')", path_accel); /* get the driver */ -- cgit v1.2.3 From b08e3d21cdca5c21396b47280b0958d6592a80d2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 08:47:12 +0200 Subject: Making lowpass filter init bullet proof --- src/lib/mathlib/math/filter/LowPassFilter2p.hpp | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/src/lib/mathlib/math/filter/LowPassFilter2p.hpp b/src/lib/mathlib/math/filter/LowPassFilter2p.hpp index 74cd5d78c..436065175 100644 --- a/src/lib/mathlib/math/filter/LowPassFilter2p.hpp +++ b/src/lib/mathlib/math/filter/LowPassFilter2p.hpp @@ -46,10 +46,18 @@ class __EXPORT LowPassFilter2p { public: // constructor - LowPassFilter2p(float sample_freq, float cutoff_freq) { + LowPassFilter2p(float sample_freq, float cutoff_freq) : + _cutoff_freq(cutoff_freq), + _a1(0.0f), + _a2(0.0f), + _b0(0.0f), + _b1(0.0f), + _b2(0.0f), + _delay_element_1(0.0f), + _delay_element_2(0.0f) + { // set initial parameters set_cutoff_frequency(sample_freq, cutoff_freq); - _delay_element_1 = _delay_element_2 = 0; } /** -- cgit v1.2.3 From 8107205b9ede8d9d36feffb50e116bb8e4dda78a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 08:47:31 +0200 Subject: device driver: Fix compile warnings --- src/drivers/device/ringbuffer.h | 4 ++++ src/drivers/device/spi.h | 5 +++++ 2 files changed, 9 insertions(+) diff --git a/src/drivers/device/ringbuffer.h b/src/drivers/device/ringbuffer.h index a9e22eaa6..b26e2e7c8 100644 --- a/src/drivers/device/ringbuffer.h +++ b/src/drivers/device/ringbuffer.h @@ -162,6 +162,10 @@ private: volatile unsigned _tail; /**< removal point in _item_size units */ unsigned _next(unsigned index); + + /* we don't want this class to be copied */ + RingBuffer(const RingBuffer&); + RingBuffer operator=(const RingBuffer&); }; RingBuffer::RingBuffer(unsigned num_items, size_t item_size) : diff --git a/src/drivers/device/spi.h b/src/drivers/device/spi.h index 54849c8c3..1d9837689 100644 --- a/src/drivers/device/spi.h +++ b/src/drivers/device/spi.h @@ -129,10 +129,15 @@ private: uint32_t _frequency; struct spi_dev_s *_dev; + /* this class does not allow copying */ + SPI(const SPI&); + SPI operator=(const SPI&); + protected: int _bus; int _transfer(uint8_t *send, uint8_t *recv, unsigned len); + }; } // namespace device -- cgit v1.2.3 From f162a3e8d406e52d42ad84ea80ca6678577b9263 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 08:47:49 +0200 Subject: LSM303D: Ensure init and constructors --- src/drivers/lsm303d/lsm303d.cpp | 13 +++++++++++++ src/drivers/lsm303d/module.mk | 2 ++ 2 files changed, 15 insertions(+) diff --git a/src/drivers/lsm303d/lsm303d.cpp b/src/drivers/lsm303d/lsm303d.cpp index d70bff69a..84ec18f28 100644 --- a/src/drivers/lsm303d/lsm303d.cpp +++ b/src/drivers/lsm303d/lsm303d.cpp @@ -461,6 +461,10 @@ private: * @return OK if the value can be supported. */ int mag_set_samplerate(unsigned frequency); + + /* this class cannot be copied */ + LSM303D(const LSM303D&); + LSM303D operator=(const LSM303D&); }; /** @@ -490,20 +494,28 @@ private: void measure(); void measure_trampoline(void *arg); + + /* this class does not allow copying due to ptr data members */ + LSM303D_mag(const LSM303D_mag&); + LSM303D_mag operator=(const LSM303D_mag&); }; LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rotation) : SPI("LSM303D", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within safety margins for LSM303D */), _mag(new LSM303D_mag(this)), + _accel_call{}, + _mag_call{}, _call_accel_interval(0), _call_mag_interval(0), _accel_reports(nullptr), _mag_reports(nullptr), + _accel_scale{}, _accel_range_m_s2(0.0f), _accel_range_scale(0.0f), _accel_samplerate(0), _accel_onchip_filter_bandwith(0), + _mag_scale{}, _mag_range_ga(0.0f), _mag_range_scale(0.0f), _mag_samplerate(0), @@ -524,6 +536,7 @@ LSM303D::LSM303D(int bus, const char* path, spi_dev_e device, enum Rotation rota _reg7_expected(0), _accel_log_fd(-1), _accel_logging_enabled(false), + _last_extreme_us(0), _last_log_us(0), _last_log_sync_us(0), _last_log_reg_us(0), diff --git a/src/drivers/lsm303d/module.mk b/src/drivers/lsm303d/module.mk index 6e9c22799..b4f3974f4 100644 --- a/src/drivers/lsm303d/module.mk +++ b/src/drivers/lsm303d/module.mk @@ -6,3 +6,5 @@ MODULE_COMMAND = lsm303d SRCS = lsm303d.cpp MODULE_STACKSIZE = 1200 + +EXTRACXXFLAGS = -Weffc++ -- cgit v1.2.3 From 5baa3690e02067380f35a551e634b67551ed214f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 08:48:10 +0200 Subject: L3GD20: Ensure init and constructors --- src/drivers/l3gd20/l3gd20.cpp | 6 ++++++ src/drivers/l3gd20/module.mk | 2 ++ 2 files changed, 8 insertions(+) diff --git a/src/drivers/l3gd20/l3gd20.cpp b/src/drivers/l3gd20/l3gd20.cpp index 2273f8aec..f72db82c0 100644 --- a/src/drivers/l3gd20/l3gd20.cpp +++ b/src/drivers/l3gd20/l3gd20.cpp @@ -330,12 +330,18 @@ private: * @return 0 on success, 1 on failure */ int self_test(); + + /* this class does not allow copying */ + L3GD20(const L3GD20&); + L3GD20 operator=(const L3GD20&); }; L3GD20::L3GD20(int bus, const char* path, spi_dev_e device, enum Rotation rotation) : SPI("L3GD20", path, bus, device, SPIDEV_MODE3, 11*1000*1000 /* will be rounded to 10.4 MHz, within margins for L3GD20 */), + _call{}, _call_interval(0), _reports(nullptr), + _gyro_scale{}, _gyro_range_scale(0.0f), _gyro_range_rad_s(0.0f), _gyro_topic(-1), diff --git a/src/drivers/l3gd20/module.mk b/src/drivers/l3gd20/module.mk index 83752e08b..5630e7aec 100644 --- a/src/drivers/l3gd20/module.mk +++ b/src/drivers/l3gd20/module.mk @@ -6,3 +6,5 @@ MODULE_COMMAND = l3gd20 SRCS = l3gd20.cpp MODULE_STACKSIZE = 1200 + +EXTRACXXFLAGS = -Weffc++ -- cgit v1.2.3 From e68200b4ba53e6594306e7925aaac3e47f0ef217 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 08:53:47 +0200 Subject: HMC driver: Full initialization --- src/drivers/hmc5883/hmc5883.cpp | 5 +++++ src/drivers/hmc5883/module.mk | 2 ++ 2 files changed, 7 insertions(+) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 0cde1045c..3a2069680 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -337,6 +337,9 @@ private: */ int check_offset(); + /* this class has pointer data members, do not allow copying it */ + HMC5883(const HMC5883&); + HMC5883 operator=(const HMC5883&); }; /* @@ -347,8 +350,10 @@ extern "C" __EXPORT int hmc5883_main(int argc, char *argv[]); HMC5883::HMC5883(int bus, const char *path, enum Rotation rotation) : I2C("HMC5883", path, bus, HMC5883L_ADDRESS, 400000), + _work{}, _measure_ticks(0), _reports(nullptr), + _scale{}, _range_scale(0), /* default range scale from counts to gauss */ _range_ga(1.3f), _collect_phase(false), diff --git a/src/drivers/hmc5883/module.mk b/src/drivers/hmc5883/module.mk index f51a2b580..5daa01dc5 100644 --- a/src/drivers/hmc5883/module.mk +++ b/src/drivers/hmc5883/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = hmc5883 SRCS = hmc5883.cpp MODULE_STACKSIZE = 1200 + +EXTRACXXFLAGS = -Weffc++ -- cgit v1.2.3 From 23dd7e752d4760a13e90ec7ed6cf003e56c4baff Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 08:54:00 +0200 Subject: airspeed driver: better init --- src/drivers/airspeed/airspeed.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/drivers/airspeed/airspeed.h b/src/drivers/airspeed/airspeed.h index 0b8e949c9..d6a88714b 100644 --- a/src/drivers/airspeed/airspeed.h +++ b/src/drivers/airspeed/airspeed.h @@ -107,6 +107,10 @@ private: RingBuffer *_reports; perf_counter_t _buffer_overflows; + /* this class has pointer data members and should not be copied */ + Airspeed(const Airspeed&); + Airspeed& operator=(const Airspeed&); + protected: virtual int probe(); -- cgit v1.2.3 From da4967e8e4256a31550a10090cbf6bfc12166b61 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 08:54:17 +0200 Subject: I2C driver: forbid copy constructor --- src/drivers/device/i2c.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/drivers/device/i2c.h b/src/drivers/device/i2c.h index 549879352..705b398b0 100644 --- a/src/drivers/device/i2c.h +++ b/src/drivers/device/i2c.h @@ -138,6 +138,9 @@ private: uint16_t _address; uint32_t _frequency; struct i2c_dev_s *_dev; + + I2C(const device::I2C&); + I2C operator=(const device::I2C&); }; } // namespace device -- cgit v1.2.3 From 7ca184de45a49ca2bde5733a54843975e193a237 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 08:54:40 +0200 Subject: MEAS airspeed: Stricter initialization and constructors --- src/drivers/meas_airspeed/meas_airspeed.cpp | 4 ++-- src/drivers/meas_airspeed/module.mk | 2 ++ 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index d643fcad6..6ab437716 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -140,9 +140,9 @@ extern "C" __EXPORT int meas_airspeed_main(int argc, char *argv[]); MEASAirspeed::MEASAirspeed(int bus, int address, const char *path) : Airspeed(bus, address, CONVERSION_INTERVAL, path), _filter(MEAS_RATE, MEAS_DRIVER_FILTER_FREQ), - _t_system_power(-1) + _t_system_power(-1), + system_power{} { - memset(&system_power, 0, sizeof(system_power)); } int diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk index 84192d1b5..2a15b669f 100644 --- a/src/drivers/meas_airspeed/module.mk +++ b/src/drivers/meas_airspeed/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = meas_airspeed SRCS = meas_airspeed.cpp MODULE_STACKSIZE = 1200 + +EXTRACXXFLAGS = -Weffc++ -- cgit v1.2.3 From 164b4ef4ce7e4452e92a3854a51b025f45319e59 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 08:58:18 +0200 Subject: MPU6K: Cleaner init --- src/drivers/mpu6000/module.mk | 2 ++ src/drivers/mpu6000/mpu6000.cpp | 9 +++++++++ 2 files changed, 11 insertions(+) diff --git a/src/drivers/mpu6000/module.mk b/src/drivers/mpu6000/module.mk index 6087e1509..5b4893b12 100644 --- a/src/drivers/mpu6000/module.mk +++ b/src/drivers/mpu6000/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = mpu6000 SRCS = mpu6000.cpp MODULE_STACKSIZE = 1200 + +EXTRACXXFLAGS = -Weffc++ diff --git a/src/drivers/mpu6000/mpu6000.cpp b/src/drivers/mpu6000/mpu6000.cpp index 442f0a37c..db9d4d7e1 100644 --- a/src/drivers/mpu6000/mpu6000.cpp +++ b/src/drivers/mpu6000/mpu6000.cpp @@ -343,6 +343,9 @@ private: */ void _set_sample_rate(uint16_t desired_sample_rate_hz); + /* do not allow to copy this class due to pointer data members */ + MPU6000(const MPU6000&); + MPU6000 operator=(const MPU6000&); }; /** @@ -369,6 +372,9 @@ private: orb_advert_t _gyro_topic; int _gyro_class_instance; + /* do not allow to copy this class due to pointer data members */ + MPU6000_gyro(const MPU6000_gyro&); + MPU6000_gyro operator=(const MPU6000_gyro&); }; /** driver 'main' command */ @@ -378,13 +384,16 @@ MPU6000::MPU6000(int bus, const char *path_accel, const char *path_gyro, spi_dev SPI("MPU6000", path_accel, bus, device, SPIDEV_MODE3, MPU6000_LOW_BUS_SPEED), _gyro(new MPU6000_gyro(this, path_gyro)), _product(0), + _call{}, _call_interval(0), _accel_reports(nullptr), + _accel_scale{}, _accel_range_scale(0.0f), _accel_range_m_s2(0.0f), _accel_topic(-1), _accel_class_instance(-1), _gyro_reports(nullptr), + _gyro_scale{}, _gyro_range_scale(0.0f), _gyro_range_rad_s(0.0f), _sample_rate(1000), -- cgit v1.2.3 From 85ccecea9c67b9f0a61fa46ec8dee324114077c1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 09:05:15 +0200 Subject: FMU driver: stricter init --- src/drivers/px4fmu/fmu.cpp | 5 +++++ src/drivers/px4fmu/module.mk | 2 ++ 2 files changed, 7 insertions(+) diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 8cc1141aa..82977a032 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -179,6 +179,9 @@ private: uint32_t gpio_read(void); int gpio_ioctl(file *filp, int cmd, unsigned long arg); + /* do not allow to copy due to ptr data members */ + PX4FMU(const PX4FMU&); + PX4FMU operator=(const PX4FMU&); }; const PX4FMU::GPIOConfig PX4FMU::_gpio_tab[] = { @@ -242,6 +245,7 @@ PX4FMU::PX4FMU() : _task(-1), _armed_sub(-1), _outputs_pub(-1), + _armed{}, _num_outputs(0), _primary_pwm_device(false), _task_should_exit(false), @@ -252,6 +256,7 @@ PX4FMU::PX4FMU() : _groups_subscribed(0), _control_subs{-1}, _poll_fds_num(0), + _pwm_limit{}, _failsafe_pwm{0}, _disarmed_pwm{0}, _num_failsafe_set(0), diff --git a/src/drivers/px4fmu/module.mk b/src/drivers/px4fmu/module.mk index eeb59e1a1..a60f1a434 100644 --- a/src/drivers/px4fmu/module.mk +++ b/src/drivers/px4fmu/module.mk @@ -6,3 +6,5 @@ MODULE_COMMAND = fmu SRCS = fmu.cpp MODULE_STACKSIZE = 1200 + +EXTRACXXFLAGS = -Weffc++ -- cgit v1.2.3 From c5b13b7dbcb36f75d88fa24b879c3f202d01da38 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 09:05:29 +0200 Subject: IO driver: stricter init --- src/drivers/px4io/module.mk | 2 ++ src/drivers/px4io/px4io.cpp | 5 +++++ 2 files changed, 7 insertions(+) diff --git a/src/drivers/px4io/module.mk b/src/drivers/px4io/module.mk index c14f1f783..5b838fb75 100644 --- a/src/drivers/px4io/module.mk +++ b/src/drivers/px4io/module.mk @@ -46,3 +46,5 @@ SRCS = px4io.cpp \ INCLUDE_DIRS += $(NUTTX_SRC)/arch/arm/src/stm32 $(NUTTX_SRC)/arch/arm/src/common MODULE_STACKSIZE = 1200 + +EXTRACXXFLAGS = -Weffc++ diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 7d78b0d27..711674886 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -453,6 +453,9 @@ private: */ void io_handle_vservo(uint16_t vservo, uint16_t vrssi); + /* do not allow to copy this class due to ptr data members */ + PX4IO(const PX4IO&); + PX4IO operator=(const PX4IO&); }; namespace @@ -496,6 +499,8 @@ PX4IO::PX4IO(device::Device *interface) : _to_battery(0), _to_servorail(0), _to_safety(0), + _outputs{}, + _servorail_status{}, _primary_pwm_device(false), _lockdown_override(false), _battery_amp_per_volt(90.0f / 5.0f), // this matches the 3DR current sensor -- cgit v1.2.3 From 654aaa0ca852b95e4e2bec5cf9b77ca3242d1d63 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 09:05:50 +0200 Subject: Mixer: forbid copy constructors due to ptr data members --- src/modules/systemlib/mixer/mixer.h | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/src/modules/systemlib/mixer/mixer.h b/src/modules/systemlib/mixer/mixer.h index 225570fa4..cdf60febc 100644 --- a/src/modules/systemlib/mixer/mixer.h +++ b/src/modules/systemlib/mixer/mixer.h @@ -231,6 +231,10 @@ protected: static const char * skipline(const char *buf, unsigned &buflen); private: + + /* do not allow to copy due to prt data members */ + Mixer(const Mixer&); + Mixer& operator=(const Mixer&); }; /** @@ -307,6 +311,10 @@ public: private: Mixer *_first; /**< linked list of mixers */ + + /* do not allow to copy due to pointer data members */ + MixerGroup(const MixerGroup&); + MixerGroup operator=(const MixerGroup&); }; /** @@ -424,6 +432,10 @@ private: mixer_scaler_s &scaler, uint8_t &control_group, uint8_t &control_index); + + /* do not allow to copy due to ptr data members */ + SimpleMixer(const SimpleMixer&); + SimpleMixer operator=(const SimpleMixer&); }; /** @@ -522,6 +534,9 @@ private: unsigned _rotor_count; const Rotor *_rotors; + /* do not allow to copy due to ptr data members */ + MultirotorMixer(const MultirotorMixer&); + MultirotorMixer operator=(const MultirotorMixer&); }; #endif -- cgit v1.2.3 From 02f56aae8cf34334580ade6e73bf2d58b12689f5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 09:24:09 +0200 Subject: Navigator: Enable more strict compile warnings --- src/modules/navigator/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/navigator/module.mk b/src/modules/navigator/module.mk index 637eaae59..b50198996 100644 --- a/src/modules/navigator/module.mk +++ b/src/modules/navigator/module.mk @@ -54,3 +54,5 @@ SRCS = navigator_main.cpp \ INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink MODULE_STACKSIZE = 1200 + +EXTRACXXFLAGS = -Weffc++ -- cgit v1.2.3 From 3ca15ab157b395b00ff225e419ae662551bc6b81 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 09:24:31 +0200 Subject: Controllib block: Make copy constructor private --- src/modules/controllib/block/Block.hpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/modules/controllib/block/Block.hpp b/src/modules/controllib/block/Block.hpp index 736698e21..9bd80b15b 100644 --- a/src/modules/controllib/block/Block.hpp +++ b/src/modules/controllib/block/Block.hpp @@ -93,6 +93,11 @@ protected: List _subscriptions; List _publications; List _params; + +private: + /* this class has pointer data members and should not be copied (private constructor) */ + Block(const control::Block&); + Block operator=(const control::Block&); }; class __EXPORT SuperBlock : -- cgit v1.2.3 From 63c6e31ba70170029549d60b6ce3b235692ccc80 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 09:24:50 +0200 Subject: Fix the most obvious compile warnings --- src/modules/navigator/navigator.h | 6 ++++++ src/modules/navigator/navigator_main.cpp | 16 ++++++++-------- src/modules/navigator/navigator_mode.h | 6 ++++++ 3 files changed, 20 insertions(+), 8 deletions(-) diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index bf6e2ea0e..8edbb63b3 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -222,5 +222,11 @@ private: * Publish a new position setpoint triplet for position controllers */ void publish_position_setpoint_triplet(); + + /* this class has ptr data members, so it should not be copied, + * consequently the copy constructors are private. + */ + Navigator(const Navigator&); + Navigator operator=(const Navigator&); }; #endif diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 1a5ba4c1a..824ed912d 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -106,16 +106,16 @@ Navigator::Navigator() : _onboard_mission_sub(-1), _offboard_mission_sub(-1), _pos_sp_triplet_pub(-1), - _vstatus({}), - _control_mode({}), - _global_pos({}), - _home_pos({}), - _mission_item({}), - _nav_caps({}), - _pos_sp_triplet({}), + _vstatus{}, + _control_mode{}, + _global_pos{}, + _home_pos{}, + _mission_item{}, + _nav_caps{}, + _pos_sp_triplet{}, _mission_item_valid(false), _loop_perf(perf_alloc(PC_ELAPSED, "navigator")), - _geofence({}), + _geofence{}, _geofence_violation_warning_sent(false), _fence_valid(false), _inside_fence(true), diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h index a7ba79bba..de5545dcb 100644 --- a/src/modules/navigator/navigator_mode.h +++ b/src/modules/navigator/navigator_mode.h @@ -88,6 +88,12 @@ protected: private: bool _first_run; + + /* this class has ptr data members, so it should not be copied, + * consequently the copy constructors are private. + */ + NavigatorMode(const NavigatorMode&); + NavigatorMode operator=(const NavigatorMode&); }; #endif -- cgit v1.2.3 From d39d5cc9da99ec17251428d57d232c30564a663b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 16 Jul 2014 11:26:32 +0200 Subject: SYS_EXT_MAG parameter added for magnetometer selection --- ROMFS/px4fmu_common/init.d/rc.sensors | 27 +++++++++++++++++---------- src/modules/systemlib/system_params.c | 11 +++++++++++ 2 files changed, 28 insertions(+), 10 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index be54ea98b..f50e9aff7 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -6,12 +6,6 @@ ms5611 start adc start -# Mag might be external -if hmc5883 start -then - echo "[init] Using HMC5883" -fi - if mpu6000 start then echo "[init] Using MPU6000" @@ -22,12 +16,25 @@ then echo "[init] Using L3GD20(H)" fi -if ver hwcmp PX4FMU_V2 +# Use selected (internal/external) magnetometer +if param compare SYS_EXT_MAG 0 then - # IMPORTANT: EXTERNAL BUSES SHOULD BE SCANNED FIRST - if lsm303d start + if hmc5883 -I start + then + echo "[init] Using internal HMC5883" + fi + + if ver hwcmp PX4FMU_V2 + then + if lsm303d start + then + echo "[init] Using internal LSM303D" + fi + fi +else + if hmc5883 -X start then - echo "[init] Using LSM303D" + echo "[init] Using external HMC5883" fi fi diff --git a/src/modules/systemlib/system_params.c b/src/modules/systemlib/system_params.c index 702e435ac..8cb923620 100644 --- a/src/modules/systemlib/system_params.c +++ b/src/modules/systemlib/system_params.c @@ -82,3 +82,14 @@ PARAM_DEFINE_INT32(SYS_USE_IO, 1); * @group System */ PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2); + +/** +* Set usage of external magnetometer +* +* Set to 1 to use external magnetometer instead of internal one. +* +* @min 0 +* @max 1 +* @group System +*/ +PARAM_DEFINE_INT32(SYS_EXT_MAG, 0); -- cgit v1.2.3 From 0c5ce3d3a23a32556b38bb0936b315d12290e4ba Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 13:42:47 +0200 Subject: Hotfix: Allow the HMC5883 driver to continue to operate in auto mode --- src/drivers/hmc5883/hmc5883.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/src/drivers/hmc5883/hmc5883.cpp b/src/drivers/hmc5883/hmc5883.cpp index 4aef43102..03a7e6f37 100644 --- a/src/drivers/hmc5883/hmc5883.cpp +++ b/src/drivers/hmc5883/hmc5883.cpp @@ -1341,8 +1341,8 @@ namespace hmc5883 #endif const int ERROR = -1; -HMC5883 *g_dev_int; -HMC5883 *g_dev_ext; +HMC5883 *g_dev_int = nullptr; +HMC5883 *g_dev_ext = nullptr; void start(int bus, enum Rotation rotation); void test(int bus); @@ -1378,6 +1378,11 @@ start(int bus, enum Rotation rotation) errx(0, "already started internal"); g_dev_int = new HMC5883(PX4_I2C_BUS_ONBOARD, HMC5883L_DEVICE_PATH_INT, rotation); if (g_dev_int != nullptr && OK != g_dev_int->init()) { + + /* tear down the failing onboard instance */ + delete g_dev_int; + g_dev_int = nullptr; + if (bus == PX4_I2C_BUS_ONBOARD) { goto fail; } -- cgit v1.2.3 From 698fcb6b8687b5901145ec90462297c398fbf5c3 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 16 Jul 2014 14:22:48 +0200 Subject: commander: only warn about lost link if link was working before --- src/modules/commander/commander.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 0c4d48dea..953feec2a 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1441,7 +1441,7 @@ int commander_thread_main(int argc, char *argv[]) /* data links check */ bool have_link = false; for (int i = 0; i < TELEMETRY_STATUS_ORB_ID_NUM; i++) { - if (hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) { + if (telemetry_last_heartbeat[i] != 0 && hrt_elapsed_time(&telemetry_last_heartbeat[i]) < DL_TIMEOUT) { /* handle the case where data link was regained */ if (telemetry_lost[i]) { mavlink_log_critical(mavlink_fd, "data link %i regained", i); -- cgit v1.2.3 From c6c9c49823a4c19e156f4ce70bde781890ab04f9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 14:58:43 +0200 Subject: Implement the external mag param in a fashion that retains backward compatibility --- ROMFS/px4fmu_common/init.d/rc.sensors | 34 ++++++++++++++++++++++------------ src/modules/sensors/sensor_params.c | 13 +++++++++++++ src/modules/systemlib/system_params.c | 11 ----------- 3 files changed, 35 insertions(+), 23 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index f50e9aff7..121dc89d3 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -8,33 +8,43 @@ adc start if mpu6000 start then - echo "[init] Using MPU6000" + echo "Internal MPU6000" fi if l3gd20 start then - echo "[init] Using L3GD20(H)" + echo "Internal L3GD20(H)" fi -# Use selected (internal/external) magnetometer -if param compare SYS_EXT_MAG 0 +# MAG selection +if param compare SENS_EXT_MAG 2 then if hmc5883 -I start then - echo "[init] Using internal HMC5883" + echo "Internal HMC5883" fi - - if ver hwcmp PX4FMU_V2 +else + # Use only external as primary + if param compare SENS_EXT_MAG 1 then - if lsm303d start + if hmc5883 -X start + then + echo "External HMC5883" + fi + else + # auto-detect the primary, prefer external + if hmc5883 start then - echo "[init] Using internal LSM303D" + echo "Default HMC5883" fi fi -else - if hmc5883 -X start +fi + +if ver hwcmp PX4FMU_V2 +then + if lsm303d start then - echo "[init] Using external HMC5883" + echo "Internal LSM303D" fi fi diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c index 38b190761..7ce6ef5ef 100644 --- a/src/modules/sensors/sensor_params.c +++ b/src/modules/sensors/sensor_params.c @@ -292,6 +292,19 @@ PARAM_DEFINE_FLOAT(SENS_BOARD_Z_OFF, 0.0f); */ PARAM_DEFINE_INT32(SENS_EXT_MAG_ROT, 0); +/** +* Set usage of external magnetometer +* +* * Set to 0 (default) to auto-detect (will try to get the external as primary) +* * Set to 1 to force the external magnetometer as primary +* * Set to 2 to force the internal magnetometer as primary +* +* @min 0 +* @max 2 +* @group Sensor Calibration +*/ +PARAM_DEFINE_INT32(SENS_EXT_MAG, 0); + /** * RC Channel 1 Minimum diff --git a/src/modules/systemlib/system_params.c b/src/modules/systemlib/system_params.c index 8cb923620..702e435ac 100644 --- a/src/modules/systemlib/system_params.c +++ b/src/modules/systemlib/system_params.c @@ -82,14 +82,3 @@ PARAM_DEFINE_INT32(SYS_USE_IO, 1); * @group System */ PARAM_DEFINE_INT32(SYS_RESTART_TYPE, 2); - -/** -* Set usage of external magnetometer -* -* Set to 1 to use external magnetometer instead of internal one. -* -* @min 0 -* @max 1 -* @group System -*/ -PARAM_DEFINE_INT32(SYS_EXT_MAG, 0); -- cgit v1.2.3 From ede1deaed6303c9ba22663fec950b9a2a66c53e5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 15:02:25 +0200 Subject: Add support for external sensors in startup --- ROMFS/px4fmu_common/init.d/rc.sensors | 15 +++++++++++++++ 1 file changed, 15 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 121dc89d3..5a755b89e 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -6,11 +6,21 @@ ms5611 start adc start +if mpu6000 -X start +then + echo "External MPU6000" +fi + if mpu6000 start then echo "Internal MPU6000" fi +if l3gd20 -X start +then + echo "External L3GD20(H)" +fi + if l3gd20 start then echo "Internal L3GD20(H)" @@ -42,6 +52,11 @@ fi if ver hwcmp PX4FMU_V2 then + if lsm303d -X start + then + echo "External LSM303D" + fi + if lsm303d start then echo "Internal LSM303D" -- cgit v1.2.3 From 0b81d9883a67a6277d85a603fde4ebbbc001d20f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 15:17:33 +0200 Subject: Strip excessive binary text to save some flash, start all three sensor sets --- ROMFS/px4fmu_common/init.d/rc.sensors | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.sensors b/ROMFS/px4fmu_common/init.d/rc.sensors index 5a755b89e..ecb408a54 100644 --- a/ROMFS/px4fmu_common/init.d/rc.sensors +++ b/ROMFS/px4fmu_common/init.d/rc.sensors @@ -8,22 +8,18 @@ adc start if mpu6000 -X start then - echo "External MPU6000" fi if mpu6000 start then - echo "Internal MPU6000" fi if l3gd20 -X start then - echo "External L3GD20(H)" fi if l3gd20 start then - echo "Internal L3GD20(H)" fi # MAG selection @@ -31,7 +27,6 @@ if param compare SENS_EXT_MAG 2 then if hmc5883 -I start then - echo "Internal HMC5883" fi else # Use only external as primary @@ -39,13 +34,11 @@ else then if hmc5883 -X start then - echo "External HMC5883" fi else # auto-detect the primary, prefer external if hmc5883 start then - echo "Default HMC5883" fi fi fi @@ -54,12 +47,10 @@ if ver hwcmp PX4FMU_V2 then if lsm303d -X start then - echo "External LSM303D" fi if lsm303d start then - echo "Internal LSM303D" fi fi @@ -70,11 +61,9 @@ then else if ets_airspeed start then - echo "[init] Using ETS airspeed sensor (bus 3)" else if ets_airspeed start -b 1 then - echo "[init] Using ETS airspeed sensor (bus 1)" fi fi fi -- cgit v1.2.3 From c2565d998359c29a66c9ebbc641ea748186c7455 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 15:17:54 +0200 Subject: PCA8574: flash efficiency --- src/drivers/pca8574/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/pca8574/module.mk b/src/drivers/pca8574/module.mk index 825ee9bb7..c53ed9ab2 100644 --- a/src/drivers/pca8574/module.mk +++ b/src/drivers/pca8574/module.mk @@ -4,3 +4,5 @@ MODULE_COMMAND = pca8574 SRCS = pca8574.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From ca98070f8b479f5d643d810a077ad09e84d32721 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 16 Jul 2014 15:18:07 +0200 Subject: RGBLED: flash efficiency --- src/drivers/rgbled/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/drivers/rgbled/module.mk b/src/drivers/rgbled/module.mk index 39b53ec9e..c287e35f3 100644 --- a/src/drivers/rgbled/module.mk +++ b/src/drivers/rgbled/module.mk @@ -4,3 +4,5 @@ MODULE_COMMAND = rgbled SRCS = rgbled.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From d9e3c9423e7d78a71acb31b0a2b3f9cc8b31a55d Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Wed, 16 Jul 2014 23:41:13 -0400 Subject: Clean up mavlink module Deal with all mavlink module compiler warnings. No critical errors found --- src/modules/mavlink/mavlink_messages.cpp | 144 +++++++++++++++++++++++++++++++ 1 file changed, 144 insertions(+) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 7c864f127..6885bebde 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -258,7 +258,16 @@ private: MavlinkOrbSubscription *status_sub; MavlinkOrbSubscription *pos_sp_triplet_sub; + /* do not allow top copying this class */ + MavlinkStreamHeartbeat(MavlinkStreamHeartbeat &); + MavlinkStreamHeartbeat& operator = (const MavlinkStreamHeartbeat &); + protected: + explicit MavlinkStreamHeartbeat() : MavlinkStream(), + status_sub(nullptr), + pos_sp_triplet_sub(nullptr) + {} + void subscribe(Mavlink *mavlink) { status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); @@ -322,7 +331,15 @@ public: private: MavlinkOrbSubscription *status_sub; + /* do not allow top copying this class */ + MavlinkStreamSysStatus(MavlinkStreamSysStatus &); + MavlinkStreamSysStatus& operator = (const MavlinkStreamSysStatus &); + protected: + explicit MavlinkStreamSysStatus() : MavlinkStream(), + status_sub(nullptr) + {} + void subscribe(Mavlink *mavlink) { status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); @@ -384,8 +401,13 @@ private: uint64_t mag_timestamp; uint64_t baro_timestamp; + /* do not allow top copying this class */ + MavlinkStreamHighresIMU(MavlinkStreamHighresIMU &); + MavlinkStreamHighresIMU& operator = (const MavlinkStreamHighresIMU &); + protected: explicit MavlinkStreamHighresIMU() : MavlinkStream(), + sensor_sub(nullptr), sensor_time(0), accel_timestamp(0), gyro_timestamp(0), @@ -469,8 +491,14 @@ private: MavlinkOrbSubscription *att_sub; uint64_t att_time; + /* do not allow top copying this class */ + MavlinkStreamAttitude(MavlinkStreamAttitude &); + MavlinkStreamAttitude& operator = (const MavlinkStreamAttitude &); + + protected: explicit MavlinkStreamAttitude() : MavlinkStream(), + att_sub(nullptr), att_time(0) {} @@ -520,8 +548,13 @@ private: MavlinkOrbSubscription *att_sub; uint64_t att_time; + /* do not allow top copying this class */ + MavlinkStreamAttitudeQuaternion(MavlinkStreamAttitudeQuaternion &); + MavlinkStreamAttitudeQuaternion& operator = (const MavlinkStreamAttitudeQuaternion &); + protected: explicit MavlinkStreamAttitudeQuaternion() : MavlinkStream(), + att_sub(nullptr), att_time(0) {} @@ -589,12 +622,21 @@ private: MavlinkOrbSubscription *airspeed_sub; uint64_t airspeed_time; + /* do not allow top copying this class */ + MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &); + MavlinkStreamVFRHUD& operator = (const MavlinkStreamVFRHUD &); + protected: explicit MavlinkStreamVFRHUD() : MavlinkStream(), + att_sub(nullptr), att_time(0), + pos_sub(nullptr), pos_time(0), + armed_sub(nullptr), armed_time(0), + act_sub(nullptr), act_time(0), + airspeed_sub(nullptr), airspeed_time(0) {} @@ -665,8 +707,13 @@ private: MavlinkOrbSubscription *gps_sub; uint64_t gps_time; + /* do not allow top copying this class */ + MavlinkStreamGPSRawInt(MavlinkStreamGPSRawInt &); + MavlinkStreamGPSRawInt& operator = (const MavlinkStreamGPSRawInt &); + protected: explicit MavlinkStreamGPSRawInt() : MavlinkStream(), + gps_sub(nullptr), gps_time(0) {} @@ -726,9 +773,15 @@ private: MavlinkOrbSubscription *home_sub; uint64_t home_time; + /* do not allow top copying this class */ + MavlinkStreamGlobalPositionInt(MavlinkStreamGlobalPositionInt &); + MavlinkStreamGlobalPositionInt& operator = (const MavlinkStreamGlobalPositionInt &); + protected: explicit MavlinkStreamGlobalPositionInt() : MavlinkStream(), + pos_sub(nullptr), pos_time(0), + home_sub(nullptr), home_time(0) {} @@ -789,8 +842,13 @@ private: MavlinkOrbSubscription *pos_sub; uint64_t pos_time; + /* do not allow top copying this class */ + MavlinkStreamLocalPositionNED(MavlinkStreamLocalPositionNED &); + MavlinkStreamLocalPositionNED& operator = (const MavlinkStreamLocalPositionNED &); + protected: explicit MavlinkStreamLocalPositionNED() : MavlinkStream(), + pos_sub(nullptr), pos_time(0) {} @@ -845,8 +903,13 @@ private: MavlinkOrbSubscription *pos_sub; uint64_t pos_time; + /* do not allow top copying this class */ + MavlinkStreamViconPositionEstimate(MavlinkStreamViconPositionEstimate &); + MavlinkStreamViconPositionEstimate& operator = (const MavlinkStreamViconPositionEstimate &); + protected: explicit MavlinkStreamViconPositionEstimate() : MavlinkStream(), + pos_sub(nullptr), pos_time(0) {} @@ -899,7 +962,15 @@ public: private: MavlinkOrbSubscription *home_sub; + /* do not allow top copying this class */ + MavlinkStreamGPSGlobalOrigin(MavlinkStreamGPSGlobalOrigin &); + MavlinkStreamGPSGlobalOrigin& operator = (const MavlinkStreamGPSGlobalOrigin &); + protected: + explicit MavlinkStreamGPSGlobalOrigin() : MavlinkStream(), + home_sub(nullptr) + {} + void subscribe(Mavlink *mavlink) { home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); @@ -962,8 +1033,13 @@ private: MavlinkOrbSubscription *act_sub; uint64_t act_time; + /* do not allow top copying this class */ + MavlinkStreamServoOutputRaw(MavlinkStreamServoOutputRaw &); + MavlinkStreamServoOutputRaw& operator = (const MavlinkStreamServoOutputRaw &); + protected: explicit MavlinkStreamServoOutputRaw() : MavlinkStream(), + act_sub(nullptr), act_time(0) {} @@ -1033,10 +1109,17 @@ private: MavlinkOrbSubscription *act_sub; uint64_t act_time; + /* do not allow top copying this class */ + MavlinkStreamHILControls(MavlinkStreamHILControls &); + MavlinkStreamHILControls& operator = (const MavlinkStreamHILControls &); + protected: explicit MavlinkStreamHILControls() : MavlinkStream(), + status_sub(nullptr), status_time(0), + pos_sp_triplet_sub(nullptr), pos_sp_triplet_time(0), + act_sub(nullptr), act_time(0) {} @@ -1159,7 +1242,15 @@ public: private: MavlinkOrbSubscription *pos_sp_triplet_sub; + /* do not allow top copying this class */ + MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &); + MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &); + protected: + explicit MavlinkStreamGlobalPositionSetpointInt() : MavlinkStream(), + pos_sp_triplet_sub(nullptr) + {} + void subscribe(Mavlink *mavlink) { pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); @@ -1208,8 +1299,13 @@ private: MavlinkOrbSubscription *pos_sp_sub; uint64_t pos_sp_time; + /* do not allow top copying this class */ + MavlinkStreamLocalPositionSetpoint(MavlinkStreamLocalPositionSetpoint &); + MavlinkStreamLocalPositionSetpoint& operator = (const MavlinkStreamLocalPositionSetpoint &); + protected: explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(), + pos_sp_sub(nullptr), pos_sp_time(0) {} @@ -1261,8 +1357,13 @@ private: MavlinkOrbSubscription *att_sp_sub; uint64_t att_sp_time; + /* do not allow top copying this class */ + MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &); + MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &); + protected: explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(), + att_sp_sub(nullptr), att_sp_time(0) {} @@ -1314,8 +1415,13 @@ private: MavlinkOrbSubscription *att_rates_sp_sub; uint64_t att_rates_sp_time; + /* do not allow top copying this class */ + MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &); + MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &); + protected: explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(), + att_rates_sp_sub(nullptr), att_rates_sp_time(0) {} @@ -1367,8 +1473,13 @@ private: MavlinkOrbSubscription *rc_sub; uint64_t rc_time; + /* do not allow top copying this class */ + MavlinkStreamRCChannelsRaw(MavlinkStreamRCChannelsRaw &); + MavlinkStreamRCChannelsRaw& operator = (const MavlinkStreamRCChannelsRaw &); + protected: explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(), + rc_sub(nullptr), rc_time(0) {} @@ -1456,8 +1567,13 @@ private: MavlinkOrbSubscription *manual_sub; uint64_t manual_time; + /* do not allow top copying this class */ + MavlinkStreamManualControl(MavlinkStreamManualControl &); + MavlinkStreamManualControl& operator = (const MavlinkStreamManualControl &); + protected: explicit MavlinkStreamManualControl() : MavlinkStream(), + manual_sub(nullptr), manual_time(0) {} @@ -1510,8 +1626,13 @@ private: MavlinkOrbSubscription *flow_sub; uint64_t flow_time; + /* do not allow top copying this class */ + MavlinkStreamOpticalFlow(MavlinkStreamOpticalFlow &); + MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &); + protected: explicit MavlinkStreamOpticalFlow() : MavlinkStream(), + flow_sub(nullptr), flow_time(0) {} @@ -1563,8 +1684,13 @@ private: MavlinkOrbSubscription *att_ctrl_sub; uint64_t att_ctrl_time; + /* do not allow top copying this class */ + MavlinkStreamAttitudeControls(MavlinkStreamAttitudeControls &); + MavlinkStreamAttitudeControls& operator = (const MavlinkStreamAttitudeControls &); + protected: explicit MavlinkStreamAttitudeControls() : MavlinkStream(), + att_ctrl_sub(nullptr), att_ctrl_time(0) {} @@ -1626,8 +1752,13 @@ private: MavlinkOrbSubscription *debug_sub; uint64_t debug_time; + /* do not allow top copying this class */ + MavlinkStreamNamedValueFloat(MavlinkStreamNamedValueFloat &); + MavlinkStreamNamedValueFloat& operator = (const MavlinkStreamNamedValueFloat &); + protected: explicit MavlinkStreamNamedValueFloat() : MavlinkStream(), + debug_sub(nullptr), debug_time(0) {} @@ -1678,7 +1809,15 @@ public: private: MavlinkOrbSubscription *status_sub; + /* do not allow top copying this class */ + MavlinkStreamCameraCapture(MavlinkStreamCameraCapture &); + MavlinkStreamCameraCapture& operator = (const MavlinkStreamCameraCapture &); + protected: + explicit MavlinkStreamCameraCapture() : MavlinkStream(), + status_sub(nullptr) + {} + void subscribe(Mavlink *mavlink) { status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); @@ -1729,8 +1868,13 @@ private: MavlinkOrbSubscription *range_sub; uint64_t range_time; + /* do not allow top copying this class */ + MavlinkStreamDistanceSensor(MavlinkStreamDistanceSensor &); + MavlinkStreamDistanceSensor& operator = (const MavlinkStreamDistanceSensor &); + protected: explicit MavlinkStreamDistanceSensor() : MavlinkStream(), + range_sub(nullptr), range_time(0) {} -- cgit v1.2.3 From 878fd1d7134fb53c358c0289ff25c9a6633c73ae Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 17 Jul 2014 09:50:11 +0200 Subject: navigator: members initialization fixed --- src/modules/navigator/navigator_main.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 824ed912d..93cbfd7b1 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -105,6 +105,7 @@ Navigator::Navigator() : _control_mode_sub(-1), _onboard_mission_sub(-1), _offboard_mission_sub(-1), + _param_update_sub(-1), _pos_sp_triplet_pub(-1), _vstatus{}, _control_mode{}, @@ -124,6 +125,8 @@ Navigator::Navigator() : _loiter(this, "LOI"), _rtl(this, "RTL"), _offboard(this, "OFF"), + _can_loiter_at_sp(false), + _pos_sp_triplet_updated(false), _param_loiter_radius(this, "LOITER_RAD"), _param_acceptance_radius(this, "ACC_RAD") { -- cgit v1.2.3 From facffe2b9eeee24f712119be91ff8aea99cfde0f Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 17 Jul 2014 17:38:04 +0200 Subject: mtecs: add altitude prefiltering --- src/modules/fw_pos_control_l1/mtecs/mTecs.cpp | 10 ++++++++-- src/modules/fw_pos_control_l1/mtecs/mTecs.h | 1 + src/modules/fw_pos_control_l1/mtecs/mTecs_params.c | 7 +++++++ src/modules/sdlog2/sdlog2.c | 1 + src/modules/sdlog2/sdlog2_messages.h | 3 ++- src/modules/uORB/topics/tecs_status.h | 1 + 6 files changed, 20 insertions(+), 3 deletions(-) diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp index 2e37d166e..749f57a2b 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp @@ -59,6 +59,7 @@ mTecs::mTecs() : _controlAltitude(this, "FPA", true), _controlAirSpeed(this, "ACC"), _flightPathAngleLowpass(this, "FPA_LP"), + _altitudeLowpass(this, "ALT_LP"), _airspeedLowpass(this, "A_LP"), _airspeedDerivative(this, "AD"), _throttleSp(0.0f), @@ -93,18 +94,23 @@ int mTecs::updateAltitudeSpeed(float flightPathAngle, float altitude, float alti /* time measurement */ updateTimeMeasurement(); + /* Filter altitude */ + float altitudeFiltered = _altitudeLowpass.update(altitude); + + /* calculate flight path angle setpoint from altitude setpoint */ - float flightPathAngleSp = _controlAltitude.update(altitudeSp - altitude); + float flightPathAngleSp = _controlAltitude.update(altitudeSp - altitudeFiltered); /* Debug output */ if (_counter % 10 == 0) { debug("***"); - debug("updateAltitudeSpeed: altitudeSp %.4f, altitude %.4f, flightPathAngleSp %.4f", (double)altitudeSp, (double)altitude, (double)flightPathAngleSp); + debug("updateAltitudeSpeed: altitudeSp %.4f, altitude %.4f, altitude filtered %.4f, flightPathAngleSp %.4f", (double)altitudeSp, (double)altitude, (double)altitudeFiltered, (double)flightPathAngleSp); } /* Write part of the status message */ _status.altitudeSp = altitudeSp; _status.altitude = altitude; + _status.altitudeFiltered = altitudeFiltered; /* use flightpath angle setpoint for total energy control */ diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.h b/src/modules/fw_pos_control_l1/mtecs/mTecs.h index efa89a5d3..ae6867d38 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.h +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.h @@ -115,6 +115,7 @@ protected: /* Other calculation Blocks */ control::BlockLowPass _flightPathAngleLowpass; /**< low pass filter for the flight path angle */ + control::BlockLowPass _altitudeLowpass; /**< low pass filter for altitude */ control::BlockLowPass _airspeedLowpass; /**< low pass filter for airspeed */ control::BlockDerivative _airspeedDerivative; /**< airspeed derivative calulation */ diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c index 5b9238780..4ca31fe20 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c @@ -174,6 +174,13 @@ PARAM_DEFINE_FLOAT(MT_PIT_MIN, -45.0f); */ PARAM_DEFINE_FLOAT(MT_PIT_MAX, 20.0f); +/** + * Lowpass (cutoff freq.) for altitude + * + * @group mTECS + */ +PARAM_DEFINE_FLOAT(MT_ALT_LP, 1.0f); + /** * Lowpass (cutoff freq.) for the flight path angle * diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index f534c0f4c..e0a3e7603 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -1595,6 +1595,7 @@ int sdlog2_thread_main(int argc, char *argv[]) log_msg.msg_type = LOG_TECS_MSG; log_msg.body.log_TECS.altitudeSp = buf.tecs_status.altitudeSp; log_msg.body.log_TECS.altitude = buf.tecs_status.altitude; + log_msg.body.log_TECS.altitudeFiltered = buf.tecs_status.altitudeFiltered; log_msg.body.log_TECS.flightPathAngleSp = buf.tecs_status.flightPathAngleSp; log_msg.body.log_TECS.flightPathAngle = buf.tecs_status.flightPathAngle; log_msg.body.log_TECS.flightPathAngleFiltered = buf.tecs_status.flightPathAngleFiltered; diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index b14ef04cc..853a3811f 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -334,6 +334,7 @@ struct log_GS1B_s { struct log_TECS_s { float altitudeSp; float altitude; + float altitudeFiltered; float flightPathAngleSp; float flightPathAngle; float flightPathAngleFiltered; @@ -454,7 +455,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(GS0B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"), LOG_FORMAT(GS1A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"), LOG_FORMAT(GS1B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"), - LOG_FORMAT(TECS, "ffffffffffffffB", "AltSP,Alt,FSP,F,FF,AsSP,As,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"), + LOG_FORMAT(TECS, "fffffffffffffffB", "ASP,A,AF,FSP,F,FF,AsSP,As,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"), LOG_FORMAT(WIND, "ffff", "X,Y,CovX,CovY"), /* system-level messages, ID >= 0x80 */ diff --git a/src/modules/uORB/topics/tecs_status.h b/src/modules/uORB/topics/tecs_status.h index c4d0c1874..33055018c 100644 --- a/src/modules/uORB/topics/tecs_status.h +++ b/src/modules/uORB/topics/tecs_status.h @@ -66,6 +66,7 @@ struct tecs_status_s { float altitudeSp; float altitude; + float altitudeFiltered; float flightPathAngleSp; float flightPathAngle; float flightPathAngleFiltered; -- cgit v1.2.3 From c01567c047f295e3ffea7d01a7e239ac4f79a498 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 17 Jul 2014 21:02:17 +0200 Subject: Check if waypoint altitude is relative. Fixes #1197 --- src/modules/navigator/mission_feasibility_checker.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp index dd7f4c801..d45488d5a 100644 --- a/src/modules/navigator/mission_feasibility_checker.cpp +++ b/src/modules/navigator/mission_feasibility_checker.cpp @@ -135,12 +135,15 @@ bool MissionFeasibilityChecker::checkHomePositionAltitude(dm_item_t dm_current, } } - if (home_alt > missionitem.altitude) { + /* calculate the global waypoint altitude */ + float wp_alt = (missionitem.altitude_is_relative) ? missionitem.altitude + home_alt ? missionitem.altitude; + + if (home_alt > wp_alt) { if (throw_error) { - mavlink_log_info(_mavlink_fd, "Waypoint %d below home", i); + mavlink_log_critical(_mavlink_fd, "Warning: Waypoint %d below home", i); return false; } else { - mavlink_log_info(_mavlink_fd, "#audio: warning waypoint %d below home", i); + mavlink_log_critical(_mavlink_fd, "Rejecting Mission: Waypoint %d below home", i); return true; } } -- cgit v1.2.3 From 101e7b1383b83c9b06ef147dbef1ff375c11b84f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 17 Jul 2014 21:06:42 +0200 Subject: navigator: Feedback strings / text and logic was not consistent in previous state, fixed. --- src/modules/navigator/mission_feasibility_checker.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp index d45488d5a..606521f20 100644 --- a/src/modules/navigator/mission_feasibility_checker.cpp +++ b/src/modules/navigator/mission_feasibility_checker.cpp @@ -136,14 +136,14 @@ bool MissionFeasibilityChecker::checkHomePositionAltitude(dm_item_t dm_current, } /* calculate the global waypoint altitude */ - float wp_alt = (missionitem.altitude_is_relative) ? missionitem.altitude + home_alt ? missionitem.altitude; + float wp_alt = (missionitem.altitude_is_relative) ? missionitem.altitude + home_alt : missionitem.altitude; if (home_alt > wp_alt) { if (throw_error) { - mavlink_log_critical(_mavlink_fd, "Warning: Waypoint %d below home", i); + mavlink_log_critical(_mavlink_fd, "Rejecting Mission: Waypoint %d below home", i); return false; } else { - mavlink_log_critical(_mavlink_fd, "Rejecting Mission: Waypoint %d below home", i); + mavlink_log_critical(_mavlink_fd, "Warning: Waypoint %d below home", i); return true; } } -- cgit v1.2.3 From 9559668f0fb7477e2f777beff899589a387d26c5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 17 Jul 2014 23:25:12 +0200 Subject: uORB: Add navigation state --- src/modules/uORB/topics/position_setpoint_triplet.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h index 673c0e491..4a1932180 100644 --- a/src/modules/uORB/topics/position_setpoint_triplet.h +++ b/src/modules/uORB/topics/position_setpoint_triplet.h @@ -95,6 +95,8 @@ struct position_setpoint_triplet_s struct position_setpoint_s previous; struct position_setpoint_s current; struct position_setpoint_s next; + + unsigned nav_state; /**< report the navigation state */ }; /** -- cgit v1.2.3 From b8da27561613a0890fd21e43064b457a58daaab3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 17 Jul 2014 23:25:33 +0200 Subject: Log nav mode --- src/modules/sdlog2/sdlog2.c | 25 ++++++++++++++----------- 1 file changed, 14 insertions(+), 11 deletions(-) diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index f534c0f4c..e078b47d6 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -1432,17 +1432,20 @@ int sdlog2_thread_main(int argc, char *argv[]) /* --- GLOBAL POSITION SETPOINT --- */ if (copy_if_updated(ORB_ID(position_setpoint_triplet), subs.triplet_sub, &buf.triplet)) { - log_msg.msg_type = LOG_GPSP_MSG; - log_msg.body.log_GPSP.nav_state = 0; /* TODO: Fix this */ - log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * 1e7d); - log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * 1e7d); - log_msg.body.log_GPSP.alt = buf.triplet.current.alt; - log_msg.body.log_GPSP.yaw = buf.triplet.current.yaw; - log_msg.body.log_GPSP.type = buf.triplet.current.type; - log_msg.body.log_GPSP.loiter_radius = buf.triplet.current.loiter_radius; - log_msg.body.log_GPSP.loiter_direction = buf.triplet.current.loiter_direction; - log_msg.body.log_GPSP.pitch_min = buf.triplet.current.pitch_min; - LOGBUFFER_WRITE_AND_COUNT(GPSP); + + if (buf.triplet.current.valid) { + log_msg.msg_type = LOG_GPSP_MSG; + log_msg.body.log_GPSP.nav_state = buf.triplet.nav_state; + log_msg.body.log_GPSP.lat = (int32_t)(buf.triplet.current.lat * 1e7d); + log_msg.body.log_GPSP.lon = (int32_t)(buf.triplet.current.lon * 1e7d); + log_msg.body.log_GPSP.alt = buf.triplet.current.alt; + log_msg.body.log_GPSP.yaw = buf.triplet.current.yaw; + log_msg.body.log_GPSP.type = buf.triplet.current.type; + log_msg.body.log_GPSP.loiter_radius = buf.triplet.current.loiter_radius; + log_msg.body.log_GPSP.loiter_direction = buf.triplet.current.loiter_direction; + log_msg.body.log_GPSP.pitch_min = buf.triplet.current.pitch_min; + LOGBUFFER_WRITE_AND_COUNT(GPSP); + } } /* --- VICON POSITION --- */ -- cgit v1.2.3 From ba7df4c170e069812387e08445cfa0e7789bf34d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 17 Jul 2014 23:26:04 +0200 Subject: Enable nav mode logging in navigator --- src/modules/navigator/navigator_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 93cbfd7b1..331a9a728 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -458,7 +458,7 @@ void Navigator::publish_position_setpoint_triplet() { /* update navigation state */ - /* TODO: set nav_state */ + _pos_sp_triplet.nav_state = _vstatus.nav_state; /* lazily publish the position setpoint triplet only once available */ if (_pos_sp_triplet_pub > 0) { -- cgit v1.2.3 From dc612d75c788bc8b2a90c200a13a5a5a0e3a68d9 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Fri, 18 Jul 2014 00:15:16 +0200 Subject: BlockDerivative: initialize in first run --- src/modules/controllib/blocks.cpp | 7 ++++++- src/modules/controllib/blocks.hpp | 2 ++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/src/modules/controllib/blocks.cpp b/src/modules/controllib/blocks.cpp index c6c374300..04cb023a8 100644 --- a/src/modules/controllib/blocks.cpp +++ b/src/modules/controllib/blocks.cpp @@ -293,7 +293,12 @@ int blockIntegralTrapTest() float BlockDerivative::update(float input) { - float output = _lowPass.update((input - getU()) / getDt()); + float output = 0.0f; + if (_initialized) { + output = _lowPass.update((input - getU()) / getDt()); + } else { + _initialized = true; + } setU(input); return output; } diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp index 66e929038..b0545b60a 100644 --- a/src/modules/controllib/blocks.hpp +++ b/src/modules/controllib/blocks.hpp @@ -238,6 +238,7 @@ public: BlockDerivative(SuperBlock *parent, const char *name) : SuperBlock(parent, name), _u(0), + _initialized(false), _lowPass(this, "LP") {}; virtual ~BlockDerivative() {}; @@ -249,6 +250,7 @@ public: protected: // attributes float _u; /**< previous input */ + bool _initialized; BlockLowPass _lowPass; /**< low pass filter */ }; -- cgit v1.2.3 From 6c50e510a5fcadab19a6d5ff709c0da473e4ace0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 07:28:49 +0200 Subject: Derivative fix: Comments and code style --- src/modules/controllib/blocks.cpp | 8 +++++++- src/modules/controllib/blocks.hpp | 15 +++++++++++++++ 2 files changed, 22 insertions(+), 1 deletion(-) diff --git a/src/modules/controllib/blocks.cpp b/src/modules/controllib/blocks.cpp index 04cb023a8..0175acda9 100644 --- a/src/modules/controllib/blocks.cpp +++ b/src/modules/controllib/blocks.cpp @@ -293,10 +293,16 @@ int blockIntegralTrapTest() float BlockDerivative::update(float input) { - float output = 0.0f; + float output; if (_initialized) { output = _lowPass.update((input - getU()) / getDt()); } else { + // if this is the first call to update + // we have no valid derivative + // and so we use the assumption the + // input value is not changing much, + // which is the best we can do here. + output = 0.0f; _initialized = true; } setU(input); diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp index b0545b60a..37d7832b3 100644 --- a/src/modules/controllib/blocks.hpp +++ b/src/modules/controllib/blocks.hpp @@ -242,6 +242,21 @@ public: _lowPass(this, "LP") {}; virtual ~BlockDerivative() {}; + + /** + * Update the state and get current derivative + * + * This call updates the state and gets the current + * derivative. As the derivative is only valid + * on the second call to update, it will return + * no change (0) on the first. To get a closer + * estimate of the derivative on the first call, + * call setU() one time step before using the + * return value of update(). + * + * @param input the variable to calculate the derivative of + * @return the current derivative + */ float update(float input); // accessors void setU(float u) {_u = u;} -- cgit v1.2.3 From ce78b399691d43bd150c0a5928f08c98076a3892 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 07:49:29 +0200 Subject: Remove all unused TECS parameters --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 54 ------- .../fw_pos_control_l1/fw_pos_control_l1_params.c | 169 --------------------- 2 files changed, 223 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 6c251c237..1fcab2069 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -199,19 +199,6 @@ private: float l1_period; float l1_damping; - float time_const; - float min_sink_rate; - float max_sink_rate; - float max_climb_rate; - float throttle_damp; - float integrator_gain; - float vertical_accel_limit; - float height_comp_filter_omega; - float speed_comp_filter_omega; - float roll_throttle_compensation; - float speed_weight; - float pitch_damping; - float airspeed_min; float airspeed_trim; float airspeed_max; @@ -242,19 +229,6 @@ private: param_t l1_period; param_t l1_damping; - param_t time_const; - param_t min_sink_rate; - param_t max_sink_rate; - param_t max_climb_rate; - param_t throttle_damp; - param_t integrator_gain; - param_t vertical_accel_limit; - param_t height_comp_filter_omega; - param_t speed_comp_filter_omega; - param_t roll_throttle_compensation; - param_t speed_weight; - param_t pitch_damping; - param_t airspeed_min; param_t airspeed_trim; param_t airspeed_max; @@ -470,21 +444,6 @@ FixedwingPositionControl::FixedwingPositionControl() : _parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST"); _parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT"); - _parameter_handles.time_const = param_find("FW_T_TIME_CONST"); - _parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN"); - _parameter_handles.max_sink_rate = param_find("FW_T_SINK_MAX"); - _parameter_handles.max_climb_rate = param_find("FW_T_CLMB_MAX"); - _parameter_handles.throttle_damp = param_find("FW_T_THR_DAMP"); - _parameter_handles.integrator_gain = param_find("FW_T_INTEG_GAIN"); - _parameter_handles.vertical_accel_limit = param_find("FW_T_VERT_ACC"); - _parameter_handles.height_comp_filter_omega = param_find("FW_T_HGT_OMEGA"); - _parameter_handles.speed_comp_filter_omega = param_find("FW_T_SPD_OMEGA"); - _parameter_handles.roll_throttle_compensation = param_find("FW_T_RLL2THR"); - _parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT"); - _parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP"); - _parameter_handles.heightrate_p = param_find("FW_T_HRATE_P"); - _parameter_handles.speedrate_p = param_find("FW_T_SRATE_P"); - /* fetch initial parameter values */ parameters_update(); } @@ -535,19 +494,6 @@ FixedwingPositionControl::parameters_update() param_get(_parameter_handles.throttle_land_max, &(_parameters.throttle_land_max)); - param_get(_parameter_handles.time_const, &(_parameters.time_const)); - param_get(_parameter_handles.min_sink_rate, &(_parameters.min_sink_rate)); - param_get(_parameter_handles.max_sink_rate, &(_parameters.max_sink_rate)); - param_get(_parameter_handles.throttle_damp, &(_parameters.throttle_damp)); - param_get(_parameter_handles.integrator_gain, &(_parameters.integrator_gain)); - param_get(_parameter_handles.vertical_accel_limit, &(_parameters.vertical_accel_limit)); - param_get(_parameter_handles.height_comp_filter_omega, &(_parameters.height_comp_filter_omega)); - param_get(_parameter_handles.speed_comp_filter_omega, &(_parameters.speed_comp_filter_omega)); - param_get(_parameter_handles.roll_throttle_compensation, &(_parameters.roll_throttle_compensation)); - param_get(_parameter_handles.speed_weight, &(_parameters.speed_weight)); - param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping)); - param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate)); - param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p)); param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p)); diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 52128e1b7..35b1f2ca9 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -154,175 +154,6 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); */ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f); -/** - * Maximum climb rate - * - * This is the best climb rate that the aircraft can achieve with - * the throttle set to THR_MAX and the airspeed set to the - * default value. For electric aircraft make sure this number can be - * achieved towards the end of flight when the battery voltage has reduced. - * The setting of this parameter can be checked by commanding a positive - * altitude change of 100m in loiter, RTL or guided mode. If the throttle - * required to climb is close to THR_MAX and the aircraft is maintaining - * airspeed, then this parameter is set correctly. If the airspeed starts - * to reduce, then the parameter is set to high, and if the throttle - * demand required to climb and maintain speed is noticeably less than - * FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or - * FW_THR_MAX reduced. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f); - -/** - * Minimum descent rate - * - * This is the sink rate of the aircraft with the throttle - * set to THR_MIN and flown at the same airspeed as used - * to measure FW_T_CLMB_MAX. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); - -/** - * Maximum descent rate - * - * This sets the maximum descent rate that the controller will use. - * If this value is too large, the aircraft can over-speed on descent. - * This should be set to a value that can be achieved without - * exceeding the lower pitch angle limit and without over-speeding - * the aircraft. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); - -/** - * TECS time constant - * - * This is the time constant of the TECS control algorithm (in seconds). - * Smaller values make it faster to respond, larger values make it slower - * to respond. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f); - -/** - * Throttle damping factor - * - * This is the damping gain for the throttle demand loop. - * Increase to add damping to correct for oscillations in speed and height. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f); - -/** - * Integrator gain - * - * This is the integrator gain on the control loop. - * Increasing this gain increases the speed at which speed - * and height offsets are trimmed out, but reduces damping and - * increases overshoot. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); - -/** - * Maximum vertical acceleration - * - * This is the maximum vertical acceleration (in metres/second square) - * either up or down that the controller will use to correct speed - * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) - * allows for reasonably aggressive pitch changes if required to recover - * from under-speed conditions. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); - -/** - * Complementary filter "omega" parameter for height - * - * This is the cross-over frequency (in radians/second) of the complementary - * filter used to fuse vertical acceleration and barometric height to obtain - * an estimate of height rate and height. Increasing this frequency weights - * the solution more towards use of the barometer, whilst reducing it weights - * the solution more towards use of the accelerometer data. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f); - -/** - * Complementary filter "omega" parameter for speed - * - * This is the cross-over frequency (in radians/second) of the complementary - * filter used to fuse longitudinal acceleration and airspeed to obtain an - * improved airspeed estimate. Increasing this frequency weights the solution - * more towards use of the arispeed sensor, whilst reducing it weights the - * solution more towards use of the accelerometer data. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); - -/** - * Roll -> Throttle feedforward - * - * Increasing this gain turn increases the amount of throttle that will - * be used to compensate for the additional drag created by turning. - * Ideally this should be set to approximately 10 x the extra sink rate - * in m/s created by a 45 degree bank turn. Increase this gain if - * the aircraft initially loses energy in turns and reduce if the - * aircraft initially gains energy in turns. Efficient high aspect-ratio - * aircraft (eg powered sailplanes) can use a lower value, whereas - * inefficient low aspect-ratio models (eg delta wings) can use a higher value. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f); - -/** - * Speed <--> Altitude priority - * - * This parameter adjusts the amount of weighting that the pitch control - * applies to speed vs height errors. Setting it to 0.0 will cause the - * pitch control to control height and ignore speed errors. This will - * normally improve height accuracy but give larger airspeed errors. - * Setting it to 2.0 will cause the pitch control loop to control speed - * and ignore height errors. This will normally reduce airspeed errors, - * but give larger height errors. The default value of 1.0 allows the pitch - * control to simultaneously control height and speed. - * Note to Glider Pilots - set this parameter to 2.0 (The glider will - * adjust its pitch angle to maintain airspeed, ignoring changes in height). - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); - -/** - * Pitch damping factor - * - * This is the damping gain for the pitch demand loop. Increase to add - * damping to correct for oscillations in height. The default value of 0.0 - * will work well provided the pitch to servo controller has been tuned - * properly. - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f); - -/** - * Height rate P factor - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f); - /** * Speed rate P factor * -- cgit v1.2.3 From 4a8e4d37cd926bed7b85ba92a5214f604a4ea192 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 07:55:02 +0200 Subject: Remove one left-over TECS param --- src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c | 7 ------- 1 file changed, 7 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 35b1f2ca9..27039ff51 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -154,13 +154,6 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); */ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f); -/** - * Speed rate P factor - * - * @group L1 Control - */ -PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f); - /** * Landing slope angle * -- cgit v1.2.3 From f7c330fa6073eaff7d1d7073b16a51e40f8b5f9d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 07:58:59 +0200 Subject: Remove all handles to TECS params in startup scripts --- ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil | 9 --------- ROMFS/px4fmu_common/init.d/3031_phantom | 4 ---- ROMFS/px4fmu_common/init.d/3032_skywalker_x5 | 4 ---- ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha | 4 ---- 4 files changed, 21 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil index c753ded23..941f5664a 100644 --- a/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil +++ b/ROMFS/px4fmu_common/init.d/1005_rc_fw_Malolo1.hil @@ -26,15 +26,6 @@ then param set FW_RR_P 0.1 param set FW_R_LIM 45 param set FW_R_RMAX 0 - param set FW_T_CLMB_MAX 5 - param set FW_T_HRATE_P 0.02 - param set FW_T_PTCH_DAMP 0 - param set FW_T_RLL2THR 15 - param set FW_T_SINK_MAX 5 - param set FW_T_SINK_MIN 2 - param set FW_T_SRATE_P 0.01 - param set FW_T_TIME_CONST 3 - param set FW_T_VERT_ACC 7 param set FW_YR_FF 0.0 param set FW_YR_I 0 param set FW_YR_IMAX 0.2 diff --git a/ROMFS/px4fmu_common/init.d/3031_phantom b/ROMFS/px4fmu_common/init.d/3031_phantom index 654b0bdab..31dfe7100 100644 --- a/ROMFS/px4fmu_common/init.d/3031_phantom +++ b/ROMFS/px4fmu_common/init.d/3031_phantom @@ -30,10 +30,6 @@ then param set FW_RR_P 0.08 param set FW_R_LIM 50 param set FW_R_RMAX 0 - param set FW_T_HRATE_P 0.01 - param set FW_T_RLL2THR 15 - param set FW_T_SRATE_P 0.01 - param set FW_T_TIME_CONST 5 fi set MIXER phantom diff --git a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 index 465166f25..7d0dc5bff 100644 --- a/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 +++ b/ROMFS/px4fmu_common/init.d/3032_skywalker_x5 @@ -30,10 +30,6 @@ then param set FW_RR_P 0.03 param set FW_R_LIM 60 param set FW_R_RMAX 0 - param set FW_T_HRATE_P 0.01 - param set FW_T_RLL2THR 15 - param set FW_T_SRATE_P 0.01 - param set FW_T_TIME_CONST 5 fi set MIXER FMU_X5 diff --git a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha index 7dbda54d3..9a2150403 100644 --- a/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha +++ b/ROMFS/px4fmu_common/init.d/3100_tbs_caipirinha @@ -33,10 +33,6 @@ then param set FW_RR_P 0.03 param set FW_R_LIM 60 param set FW_R_RMAX 0 - param set FW_T_HRATE_P 0.01 - param set FW_T_RLL2THR 15 - param set FW_T_SRATE_P 0.01 - param set FW_T_TIME_CONST 5 fi set MIXER FMU_Q -- cgit v1.2.3 From 90a5ae1afd25e5e31d269f0d0f5e5052f068d0b1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 08:04:13 +0200 Subject: Remove MT_ENABLED param and handles --- src/modules/fw_pos_control_l1/mtecs/mTecs.cpp | 1 - src/modules/fw_pos_control_l1/mtecs/mTecs.h | 2 -- src/modules/fw_pos_control_l1/mtecs/mTecs_params.c | 11 ----------- 3 files changed, 14 deletions(-) diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp index 749f57a2b..8f0e57e20 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp @@ -49,7 +49,6 @@ namespace fwPosctrl { mTecs::mTecs() : SuperBlock(NULL, "MT"), /* Parameters */ - _mTecsEnabled(this, "ENABLED"), _airspeedMin(this, "FW_AIRSPD_MIN", false), /* Publications */ _status(&getPublications(), ORB_ID(tecs_status)), diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.h b/src/modules/fw_pos_control_l1/mtecs/mTecs.h index ae6867d38..99830fba6 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.h +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.h @@ -90,14 +90,12 @@ public: void resetDerivatives(float airspeed); /* Accessors */ - bool getEnabled() { return _mTecsEnabled.get() > 0; } float getThrottleSetpoint() { return _throttleSp; } float getPitchSetpoint() { return _pitchSp; } float airspeedLowpassUpdate(float input) { return _airspeedLowpass.update(input); } protected: /* parameters */ - control::BlockParamInt _mTecsEnabled; /**< 1 if mTecs is enabled */ control::BlockParamFloat _airspeedMin; /**< minimal airspeed */ /* Publications */ diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c index 4ca31fe20..6e9e1d88e 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c @@ -46,17 +46,6 @@ * Controller parameters, accessible via MAVLink */ -/** - * mTECS enabled - * - * Set to 1 to enable mTECS - * - * @min 0 - * @max 1 - * @group mTECS - */ -PARAM_DEFINE_INT32(MT_ENABLED, 1); - /** * Total Energy Rate Control Feedforward * Maps the total energy rate setpoint to the throttle setpoint -- cgit v1.2.3 From 81f60329e47f8b31d9261c0ef46c09780f9d8194 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 08:07:35 +0200 Subject: Remove last reference to mtecs enabled param --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 1fcab2069..5894aeb0b 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -756,10 +756,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi if (!_was_pos_control_mode) { /* reset integrators */ - if (_mTecs.getEnabled()) { - _mTecs.resetIntegrators(); - _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s); - } + _mTecs.resetIntegrators(); + _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s); } _was_pos_control_mode = true; -- cgit v1.2.3 From 9a53fd96482bd31da98af97de5cde88127d6c7f9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 11:18:32 +0200 Subject: Add force failsafe flag --- src/modules/px4iofirmware/mixer.cpp | 9 ++++++++- src/modules/px4iofirmware/protocol.h | 5 +++++ 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/mixer.cpp b/src/modules/px4iofirmware/mixer.cpp index 2f721bf1e..606c639f9 100644 --- a/src/modules/px4iofirmware/mixer.cpp +++ b/src/modules/px4iofirmware/mixer.cpp @@ -111,7 +111,7 @@ mixer_tick(void) r_status_flags |= PX4IO_P_STATUS_FLAGS_FMU_OK; } - /* default to failsafe mixing */ + /* default to failsafe mixing - it will be forced below if flag is set */ source = MIX_FAILSAFE; /* @@ -154,6 +154,13 @@ mixer_tick(void) } } + /* + * Check if we should force failsafe - and do it if we have to + */ + if (r_setup_arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) { + source = MIX_FAILSAFE; + } + /* * Set failsafe status flag depending on mixing source */ diff --git a/src/modules/px4iofirmware/protocol.h b/src/modules/px4iofirmware/protocol.h index d5a6b1ec4..050783687 100644 --- a/src/modules/px4iofirmware/protocol.h +++ b/src/modules/px4iofirmware/protocol.h @@ -179,6 +179,7 @@ #define PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE (1 << 5) /* Output of PWM right after startup enabled to help ESCs initialize and prevent them from beeping */ #define PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED (1 << 6) /* Disable the IO-internal evaluation of the RC */ #define PX4IO_P_SETUP_ARMING_LOCKDOWN (1 << 7) /* If set, the system operates normally, but won't actuate any servos */ +#define PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE (1 << 8) /* If set, the system will always output the failsafe values */ #define PX4IO_P_SETUP_PWM_RATES 2 /* bitmask, 0 = low rate, 1 = high rate */ #define PX4IO_P_SETUP_PWM_DEFAULTRATE 3 /* 'low' PWM frame output rate in Hz */ @@ -253,6 +254,10 @@ enum { /* DSM bind states */ /* PWM failsafe values - zero disables the output */ #define PX4IO_PAGE_FAILSAFE_PWM 55 /**< 0..CONFIG_ACTUATOR_COUNT-1 */ +/* PWM failsafe values - zero disables the output */ +#define PX4IO_PAGE_SENSORS 56 /**< Sensors connected to PX4IO */ +#define PX4IO_P_SENSORS_ALTITUDE 0 /**< Altitude of an external sensor (HoTT or S.BUS2) */ + /* Debug and test page - not used in normal operation */ #define PX4IO_PAGE_TEST 127 #define PX4IO_P_TEST_LED 0 /**< set the amber LED on/off */ -- cgit v1.2.3 From 903b482378516f26ef0faa4d658597e0af2fb35d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 11:19:05 +0200 Subject: PX4IO driver: Add support to set force failsafe --- src/drivers/drv_pwm_output.h | 3 +++ src/drivers/px4io/px4io.cpp | 11 +++++++++++ 2 files changed, 14 insertions(+) diff --git a/src/drivers/drv_pwm_output.h b/src/drivers/drv_pwm_output.h index 972573f9f..84815fdfb 100644 --- a/src/drivers/drv_pwm_output.h +++ b/src/drivers/drv_pwm_output.h @@ -202,6 +202,9 @@ ORB_DECLARE(output_pwm); /** force safety switch off (to disable use of safety switch) */ #define PWM_SERVO_SET_FORCE_SAFETY_OFF _IOC(_PWM_SERVO_BASE, 23) +/** force failsafe mode (failsafe values are set immediately even if failsafe condition not met) */ +#define PWM_SERVO_SET_FORCE_FAILSAFE _IOC(_PWM_SERVO_BASE, 24) + /* * * diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index 711674886..f5ff6e55e 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2222,6 +2222,17 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg) ret = io_reg_set(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_FORCE_SAFETY_OFF, PX4IO_FORCE_SAFETY_MAGIC); break; + case PWM_SERVO_SET_FORCE_FAILSAFE: + /* force failsafe mode instantly */ + if (arg == 0) { + /* clear force failsafe flag */ + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE, 0); + } else { + /* set force failsafe flag */ + ret = io_reg_modify(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING, 0, PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE); + } + break; + case DSM_BIND_START: /* only allow DSM2, DSM-X and DSM-X with more than 7 channels */ -- cgit v1.2.3 From 5c8c58a1e6a2977b4a2f6d81928d4bfc64c87649 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 11:19:37 +0200 Subject: pwm system command: Allow to force failsave (forcefail command) --- src/systemcmds/pwm/pwm.c | 16 ++++++++++++++++ 1 file changed, 16 insertions(+) diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index e0e6ca537..77d8ef8db 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -635,7 +635,23 @@ pwm_main(int argc, char *argv[]) } exit(0); + } else if (!strcmp(argv[1], "forcefail")) { + + if (argc < 3) { + errx(1, "arg missing [on|off]"); + } else { + + if (!strcmp(argv[2], "on")) { + /* force failsafe */ + ret = ioctl(fd, PWM_SERVO_SET_FORCE_FAILSAFE, 1); + } else { + /* force failsafe */ + ret = ioctl(fd, PWM_SERVO_SET_FORCE_FAILSAFE, 0); + } + } + } + usage("specify arm|disarm|rate|failsafe|disarmed|min|max|test|info"); return 0; } -- cgit v1.2.3 From a2da34be16531404b4c4507ab71b0518a51d60c5 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 18 Jul 2014 20:53:01 +0200 Subject: Fixes #1207 --- src/modules/mavlink/mavlink_main.cpp | 31 ++++++++++++++++++++++++------- 1 file changed, 24 insertions(+), 7 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 76b5459a3..e235ff0f9 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -525,22 +525,39 @@ void Mavlink::mavlink_update_system(void) _param_component_id = param_find("MAV_COMP_ID"); _param_system_type = param_find("MAV_TYPE"); _param_use_hil_gps = param_find("MAV_USEHILGPS"); - _param_initialized = true; } /* update system and component id */ int32_t system_id; param_get(_param_system_id, &system_id); - if (system_id > 0 && system_id < 255) { - mavlink_system.sysid = system_id; - } - int32_t component_id; param_get(_param_component_id, &component_id); - if (component_id > 0 && component_id < 255) { - mavlink_system.compid = component_id; + + /* only allow system ID and component ID updates + * after reboot - not during operation */ + if (!_param_initialized) { + if (system_id > 0 && system_id < 255) { + mavlink_system.sysid = system_id; + } + + if (component_id > 0 && component_id < 255) { + mavlink_system.compid = component_id; + } + + _param_initialized = true; + } + + /* warn users that they need to reboot to take this + * into effect + */ + if (system_id != mavlink_system.sysid) { + send_statustext_critical("Save params and reboot to change SYSID"); + } + + if (component_id != mavlink_system.compid) { + send_statustext_critical("Save params and reboot to change COMPID"); } int32_t system_type; -- cgit v1.2.3 From 528253e33a49702a9c394a5b25d823e4db0a4e7d Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 18 Jul 2014 23:24:07 +0400 Subject: UAVCAN update --- uavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uavcan b/uavcan index af065e9ca..767462c99 160000 --- a/uavcan +++ b/uavcan @@ -1 +1 @@ -Subproject commit af065e9ca9e3ba9100c125d3ab739313d0500ca8 +Subproject commit 767462c9924d7afbb789dc3e4c76d31261c557d3 -- cgit v1.2.3 From a4e1a665833f566e2faaa80d221971c679b57d17 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 10:52:50 +0200 Subject: Revert "Remove last reference to mtecs enabled param" This reverts commit 81f60329e47f8b31d9261c0ef46c09780f9d8194. --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 5894aeb0b..1fcab2069 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -756,8 +756,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi if (!_was_pos_control_mode) { /* reset integrators */ - _mTecs.resetIntegrators(); - _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s); + if (_mTecs.getEnabled()) { + _mTecs.resetIntegrators(); + _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s); + } } _was_pos_control_mode = true; -- cgit v1.2.3 From 57794925fe0fcaf5736163f8ad43a4551a1a9b71 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 10:53:04 +0200 Subject: Revert "Remove MT_ENABLED param and handles" This reverts commit 90a5ae1afd25e5e31d269f0d0f5e5052f068d0b1. --- src/modules/fw_pos_control_l1/mtecs/mTecs.cpp | 1 + src/modules/fw_pos_control_l1/mtecs/mTecs.h | 2 ++ src/modules/fw_pos_control_l1/mtecs/mTecs_params.c | 11 +++++++++++ 3 files changed, 14 insertions(+) diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp index 8f0e57e20..749f57a2b 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp @@ -49,6 +49,7 @@ namespace fwPosctrl { mTecs::mTecs() : SuperBlock(NULL, "MT"), /* Parameters */ + _mTecsEnabled(this, "ENABLED"), _airspeedMin(this, "FW_AIRSPD_MIN", false), /* Publications */ _status(&getPublications(), ORB_ID(tecs_status)), diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.h b/src/modules/fw_pos_control_l1/mtecs/mTecs.h index 99830fba6..ae6867d38 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.h +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.h @@ -90,12 +90,14 @@ public: void resetDerivatives(float airspeed); /* Accessors */ + bool getEnabled() { return _mTecsEnabled.get() > 0; } float getThrottleSetpoint() { return _throttleSp; } float getPitchSetpoint() { return _pitchSp; } float airspeedLowpassUpdate(float input) { return _airspeedLowpass.update(input); } protected: /* parameters */ + control::BlockParamInt _mTecsEnabled; /**< 1 if mTecs is enabled */ control::BlockParamFloat _airspeedMin; /**< minimal airspeed */ /* Publications */ diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c index 6e9e1d88e..4ca31fe20 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c @@ -46,6 +46,17 @@ * Controller parameters, accessible via MAVLink */ +/** + * mTECS enabled + * + * Set to 1 to enable mTECS + * + * @min 0 + * @max 1 + * @group mTECS + */ +PARAM_DEFINE_INT32(MT_ENABLED, 1); + /** * Total Energy Rate Control Feedforward * Maps the total energy rate setpoint to the throttle setpoint -- cgit v1.2.3 From 322089a390f416a9936fb4ad1ad0ed4359aeaa57 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 11:29:49 +0200 Subject: Fix unused params --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 1fcab2069..0b111f7bd 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -212,9 +212,6 @@ private: float throttle_land_max; - float heightrate_p; - float speedrate_p; - float land_slope_angle; float land_H1_virt; float land_flare_alt_relative; @@ -242,9 +239,6 @@ private: param_t throttle_land_max; - param_t heightrate_p; - param_t speedrate_p; - param_t land_slope_angle; param_t land_H1_virt; param_t land_flare_alt_relative; @@ -494,9 +488,6 @@ FixedwingPositionControl::parameters_update() param_get(_parameter_handles.throttle_land_max, &(_parameters.throttle_land_max)); - param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p)); - param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p)); - param_get(_parameter_handles.land_slope_angle, &(_parameters.land_slope_angle)); param_get(_parameter_handles.land_H1_virt, &(_parameters.land_H1_virt)); param_get(_parameter_handles.land_flare_alt_relative, &(_parameters.land_flare_alt_relative)); -- cgit v1.2.3 From 689536893caea0cde8cafb3a51cd7e471338cfb0 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 19 Jul 2014 12:46:52 +0200 Subject: px4io driver: force failsafe depending on actuator armed --- src/drivers/px4io/px4io.cpp | 20 +++++++++++++------- src/modules/uORB/topics/actuator_armed.h | 3 ++- 2 files changed, 15 insertions(+), 8 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index f5ff6e55e..5ada635f3 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -1149,6 +1149,12 @@ PX4IO::io_set_arming_state() clear |= PX4IO_P_SETUP_ARMING_LOCKDOWN; } + if (armed.force_failsafe) { + set |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE; + } else { + clear |= PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE; + } + if (armed.ready_to_arm) { set |= PX4IO_P_SETUP_ARMING_IO_ARM_OK; @@ -2435,7 +2441,7 @@ PX4IO::ioctl(file * filep, int cmd, unsigned long arg) break; case PX4IO_CHECK_CRC: { - /* check IO firmware CRC against passed value */ + /* check IO firmware CRC against passed value */ uint32_t io_crc = 0; ret = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_CRC, (uint16_t *)&io_crc, 2); if (ret != OK) @@ -2695,7 +2701,7 @@ checkcrc(int argc, char *argv[]) int fd = open(argv[1], O_RDONLY); if (fd == -1) { printf("open of %s failed - %d\n", argv[1], errno); - exit(1); + exit(1); } const uint32_t app_size_max = 0xf000; uint32_t fw_crc = 0; @@ -2710,7 +2716,7 @@ checkcrc(int argc, char *argv[]) close(fd); while (nbytes < app_size_max) { uint8_t b = 0xff; - fw_crc = crc32part(&b, 1, fw_crc); + fw_crc = crc32part(&b, 1, fw_crc); nbytes++; } @@ -2723,7 +2729,7 @@ checkcrc(int argc, char *argv[]) if (ret != OK) { printf("check CRC failed - %d\n", ret); - exit(1); + exit(1); } printf("CRCs match\n"); exit(0); @@ -2753,12 +2759,12 @@ bind(int argc, char *argv[]) pulses = DSMX_BIND_PULSES; else if (!strcmp(argv[2], "dsmx8")) pulses = DSMX8_BIND_PULSES; - else + else errx(1, "unknown parameter %s, use dsm2, dsmx or dsmx8", argv[2]); // Test for custom pulse parameter if (argc > 3) pulses = atoi(argv[3]); - if (g_dev->system_status() & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) + if (g_dev->system_status() & PX4IO_P_STATUS_FLAGS_SAFETY_OFF) errx(1, "system must not be armed"); #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 @@ -2960,7 +2966,7 @@ lockdown(int argc, char *argv[]) (void)g_dev->ioctl(0, PWM_SERVO_SET_DISABLE_LOCKDOWN, 0); warnx("ACTUATORS ARE NOW SAFE IN HIL."); } - + } else { errx(1, "driver not loaded, exiting"); } diff --git a/src/modules/uORB/topics/actuator_armed.h b/src/modules/uORB/topics/actuator_armed.h index a98d3fc3a..0f6c9aca1 100644 --- a/src/modules/uORB/topics/actuator_armed.h +++ b/src/modules/uORB/topics/actuator_armed.h @@ -56,6 +56,7 @@ struct actuator_armed_s { bool armed; /**< Set to true if system is armed */ bool ready_to_arm; /**< Set to true if system is ready to be armed */ bool lockdown; /**< Set to true if actuators are forced to being disabled (due to emergency or HIL) */ + bool force_failsafe; /**< Set to true if the actuators are forced to the failsafe position */ }; /** @@ -65,4 +66,4 @@ struct actuator_armed_s { /* register this as object request broker structure */ ORB_DECLARE(actuator_armed); -#endif \ No newline at end of file +#endif -- cgit v1.2.3 From 7b3654a5764bdc2ff0e2a894d193dc59976ff828 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 19 Jul 2014 13:08:54 +0200 Subject: checkout latest mavlink master --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index d1ebe85eb..27c9f70f2 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit d1ebe85eb6bb06d0078f3e0b8144adb131263628 +Subproject commit 27c9f70f21121e352215cb441f9fb97f56333e23 -- cgit v1.2.3 From 78b8e4d59f606eb56a475b69d61da8a83613d73d Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 19 Jul 2014 13:23:35 +0200 Subject: really checkout latest mavlink master --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 27c9f70f2..04b1ad5b2 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 27c9f70f21121e352215cb441f9fb97f56333e23 +Subproject commit 04b1ad5b284d5e916858ca9f928e93d97bbf6ad9 -- cgit v1.2.3 From 3a0fc36c67ef89faa0b20e847eb16de6362ef3e8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 14:12:33 +0200 Subject: Consider the throttle load for battery voltage calculation --- src/modules/commander/commander.cpp | 11 ++++++++++- src/modules/commander/commander_helper.cpp | 10 +++++++--- src/modules/commander/commander_helper.h | 3 ++- src/modules/commander/commander_params.c | 4 ++-- 4 files changed, 21 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 953feec2a..7332c6eaa 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -918,6 +918,11 @@ int commander_thread_main(int argc, char *argv[]) struct system_power_s system_power; memset(&system_power, 0, sizeof(system_power)); + /* Subscribe to actuator controls (outputs) */ + int actuator_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); + struct actuator_controls_s actuator_controls; + memset(&actuator_controls, 0, sizeof(actuator_controls)); + control_status_leds(&status, &armed, true); /* now initialized */ @@ -1199,13 +1204,17 @@ int commander_thread_main(int argc, char *argv[]) if (updated) { orb_copy(ORB_ID(battery_status), battery_sub, &battery); + orb_copy(ORB_ID_VEHICLE_ATTITUDE_CONTROLS, actuator_controls_sub, &actuator_controls); /* only consider battery voltage if system has been running 2s and battery voltage is valid */ if (hrt_absolute_time() > start_time + 2000000 && battery.voltage_filtered_v > 0.0f) { status.battery_voltage = battery.voltage_filtered_v; status.battery_current = battery.current_a; status.condition_battery_voltage_valid = true; - status.battery_remaining = battery_remaining_estimate_voltage(battery.voltage_filtered_v, battery.discharged_mah); + + /* get throttle (if armed), as we only care about energy negative throttle also counts */ + float throttle = (armed.armed) ? fabsf(actuator_controls.control[3]) : 0.0f; + status.battery_remaining = battery_remaining_estimate_voltage(battery.voltage_filtered_v, battery.discharged_mah, throttle); } } diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index d5fe122cb..a4aafa1f6 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -281,15 +281,17 @@ void rgbled_set_pattern(rgbled_pattern_t *pattern) } } -float battery_remaining_estimate_voltage(float voltage, float discharged) +float battery_remaining_estimate_voltage(float voltage, float discharged, float throttle_normalized) { float ret = 0; static param_t bat_v_empty_h; static param_t bat_v_full_h; static param_t bat_n_cells_h; static param_t bat_capacity_h; + static param_t bat_v_load_drop_h; static float bat_v_empty = 3.2f; static float bat_v_full = 4.0f; + static float bat_v_load_drop = 0.1f; static int bat_n_cells = 3; static float bat_capacity = -1.0f; static bool initialized = false; @@ -300,20 +302,22 @@ float battery_remaining_estimate_voltage(float voltage, float discharged) bat_v_full_h = param_find("BAT_V_FULL"); bat_n_cells_h = param_find("BAT_N_CELLS"); bat_capacity_h = param_find("BAT_CAPACITY"); + bat_v_load_drop_h = param_find("BAT_V_LOAD_DROP"); initialized = true; } if (counter % 100 == 0) { param_get(bat_v_empty_h, &bat_v_empty); param_get(bat_v_full_h, &bat_v_full); + param_get(bat_v_load_drop_h, &bat_v_load_drop); param_get(bat_n_cells_h, &bat_n_cells); param_get(bat_capacity_h, &bat_capacity); } counter++; - /* remaining charge estimate based on voltage */ - float remaining_voltage = (voltage - bat_n_cells * bat_v_empty) / (bat_n_cells * (bat_v_full - bat_v_empty)); + /* remaining charge estimate based on voltage and internal resistance (drop under load) */ + float remaining_voltage = (voltage - bat_n_cells * (bat_v_empty - (bat_v_load_drop * throttle_normalized)) / (bat_n_cells * (bat_v_full - bat_v_empty)); if (bat_capacity > 0.0f) { /* if battery capacity is known, use discharged current for estimate, but don't show more than voltage estimate */ diff --git a/src/modules/commander/commander_helper.h b/src/modules/commander/commander_helper.h index a49c9e263..4a77fe487 100644 --- a/src/modules/commander/commander_helper.h +++ b/src/modules/commander/commander_helper.h @@ -80,8 +80,9 @@ void rgbled_set_pattern(rgbled_pattern_t *pattern); * * @param voltage the current battery voltage * @param discharged the discharged capacity + * @param throttle_normalized the normalized throttle magnitude from 0 to 1. Negative throttle should be converted to this range as well, as it consumes energy. * @return the estimated remaining capacity in 0..1 */ -float battery_remaining_estimate_voltage(float voltage, float discharged); +float battery_remaining_estimate_voltage(float voltage, float discharged, float throttle_normalized); #endif /* COMMANDER_HELPER_H_ */ diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 4750f9d5c..448bc53cd 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -56,7 +56,7 @@ PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f); * * @group Battery Calibration */ -PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f); +PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.3f); /** * Full cell voltage. @@ -65,7 +65,7 @@ PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f); * * @group Battery Calibration */ -PARAM_DEFINE_FLOAT(BAT_V_FULL, 3.9f); +PARAM_DEFINE_FLOAT(BAT_V_FULL, 4.15f); /** * Number of cells. -- cgit v1.2.3 From 3db78a4ab31b79f092940f4186549132a40ed855 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 14:34:19 +0200 Subject: commander: Warn at 18 and 9% battery remaining instead of 25 and 10% to not trigger the warning too early (at 50%) as it was before --- src/modules/commander/commander.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 7332c6eaa..cb447f8ce 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1276,13 +1276,13 @@ int commander_thread_main(int argc, char *argv[]) } /* if battery voltage is getting lower, warn using buzzer, etc. */ - if (status.condition_battery_voltage_valid && status.battery_remaining < 0.25f && !low_battery_voltage_actions_done) { + if (status.condition_battery_voltage_valid && status.battery_remaining < 0.18f && !low_battery_voltage_actions_done) { low_battery_voltage_actions_done = true; mavlink_log_critical(mavlink_fd, "LOW BATTERY, RETURN TO LAND ADVISED"); status.battery_warning = VEHICLE_BATTERY_WARNING_LOW; status_changed = true; - } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.1f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) { + } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.9f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) { /* critical battery voltage, this is rather an emergency, change state machine */ critical_battery_voltage_actions_done = true; mavlink_log_emergency(mavlink_fd, "CRITICAL BATTERY, LAND IMMEDIATELY"); -- cgit v1.2.3 From 5fc3bc787a495d15099e177b99c2c4d6a1a4f56c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 14:38:39 +0200 Subject: code style only: Fix indendation in mavlink.h --- src/modules/mavlink/mavlink_main.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index da989d6c5..adca0e88f 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -250,13 +250,13 @@ private: MavlinkOrbSubscription *_subscriptions; MavlinkStream *_streams; - MavlinkMissionManager *_mission_manager; + MavlinkMissionManager *_mission_manager; - orb_advert_t _mission_pub; + orb_advert_t _mission_pub; int _mission_result_sub; - MAVLINK_MODE _mode; + MAVLINK_MODE _mode; - mavlink_channel_t _channel; + mavlink_channel_t _channel; struct mavlink_logbuffer _logbuffer; unsigned int _total_counter; -- cgit v1.2.3 From de0dd71061b1b388e87c25a3d4fd0080f0c9cf8b Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 19 Jul 2014 14:39:19 +0200 Subject: pwm: add missing exit --- src/systemcmds/pwm/pwm.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index 77d8ef8db..403567cb4 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -70,7 +70,7 @@ usage(const char *reason) { if (reason != NULL) warnx("%s", reason); - errx(1, + errx(1, "usage:\n" "pwm arm|disarm|rate|failsafe|disarmed|min|max|test|info ...\n" "\n" @@ -649,7 +649,7 @@ pwm_main(int argc, char *argv[]) ret = ioctl(fd, PWM_SERVO_SET_FORCE_FAILSAFE, 0); } } - + exit(0); } usage("specify arm|disarm|rate|failsafe|disarmed|min|max|test|info"); -- cgit v1.2.3 From 0b743a9f5c29cee3b3d7c6d602091453e1091973 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 19 Jul 2014 14:39:41 +0200 Subject: parse flighttermination command --- src/modules/commander/commander.cpp | 21 ++++++++------------- src/modules/uORB/topics/vehicle_command.h | 1 + 2 files changed, 9 insertions(+), 13 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 953feec2a..04450a44f 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -546,24 +546,19 @@ bool handle_command(struct vehicle_status_s *status_local, const struct safety_s } break; -#if 0 /* Flight termination */ - case VEHICLE_CMD_DO_SET_SERVO: { //xxx: needs its own mavlink command - - //XXX: to enable the parachute, a param needs to be set - //xxx: for safety only for now, param3 is unused by VEHICLE_CMD_DO_SET_SERVO - if (armed_local->armed && cmd->param3 > 0.5 && parachute_enabled) { - transition_result_t failsafe_res = failsafe_state_transition(status, FAILSAFE_STATE_TERMINATION); - cmd_result = VEHICLE_CMD_RESULT_ACCEPTED; - + case VEHICLE_CMD_DO_FLIGHTTERMINATION: { + if (cmd->param1 > 0.5f) { + //XXX update state machine? + armed_local->force_failsafe = true; + warnx("forcing failsafe"); } else { - /* reject parachute depoyment not armed */ - cmd_result = VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED; + armed_local->force_failsafe = false; + warnx("disabling failsafe"); } - + cmd_result = VEHICLE_CMD_RESULT_ACCEPTED; } break; -#endif case VEHICLE_CMD_DO_SET_HOME: { bool use_current = cmd->param1 > 0.5f; diff --git a/src/modules/uORB/topics/vehicle_command.h b/src/modules/uORB/topics/vehicle_command.h index c21a29b13..7db33d98b 100644 --- a/src/modules/uORB/topics/vehicle_command.h +++ b/src/modules/uORB/topics/vehicle_command.h @@ -76,6 +76,7 @@ enum VEHICLE_CMD { VEHICLE_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| */ VEHICLE_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| */ VEHICLE_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| */ + VEHICLE_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately |Flight termination activated if > 0.5| Empty| Empty| Empty| Empty| Empty| Empty| */ VEHICLE_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| */ VEHICLE_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| */ VEHICLE_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| Accelerometer calibration: 0: no, 1: yes| Empty| Empty| */ -- cgit v1.2.3 From 730a520362caf9c9d3e506a31441d9921e008144 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 14:59:13 +0200 Subject: Print mavlink radio module rates --- src/modules/mavlink/mavlink_main.cpp | 51 ++++++++++++++++++++++++++++++-- src/modules/mavlink/mavlink_main.h | 10 +++++++ src/modules/mavlink/mavlink_receiver.cpp | 3 +- 3 files changed, 59 insertions(+), 5 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 76b5459a3..e25851c7d 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -247,6 +247,7 @@ Mavlink::Mavlink() : _subscribe_to_stream(nullptr), _subscribe_to_stream_rate(0.0f), _flow_control_enabled(true), + _rstatus{}, _message_buffer{}, _message_buffer_mutex{}, _param_initialized(false), @@ -424,6 +425,29 @@ Mavlink::destroy_all_instances() return OK; } +int +Mavlink::get_status_all_instances() +{ + Mavlink *inst = ::_mavlink_instances; + + unsigned iterations = 0; + + warnx("waiting for instances to stop"); + + while (inst != nullptr) { + + printf("instance #%u:\n", iterations); + inst->display_status(); + + /* move on */ + inst = inst->next; + iterations++; + } + + /* return an error if there are no instances */ + return (iterations == 0); +} + bool Mavlink::instance_exists(const char *device_name, Mavlink *self) { @@ -1395,7 +1419,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("GPS_GLOBAL_ORIGIN", 0.5f); configure_stream("HIGHRES_IMU", 1.0f * rate_mult); configure_stream("ATTITUDE", 10.0f * rate_mult); - configure_stream("VFR_HUD", 10.0f * rate_mult); + configure_stream("VFR_HUD", 8.0f * rate_mult); configure_stream("GPS_RAW_INT", 1.0f * rate_mult); configure_stream("GLOBAL_POSITION_INT", 3.0f * rate_mult); configure_stream("LOCAL_POSITION_NED", 3.0f * rate_mult); @@ -1665,6 +1689,27 @@ void Mavlink::display_status() { warnx("running"); + + if (_rstatus.timestamp > 0) { + printf("\ttime:\t%llu\tus\n", _rstatus.heartbeat_time); + + switch (_rstatus.type) { + case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: + printf("\t3DR RADIO\n"); + break; + default: + printf("\tUNKNOWN RADIO\n"); + break; + } + + printf("\trssi:\t%d\t\n", _rstatus.rssi); + printf("\tremote rssi:\t%u\tus\n", _rstatus.remote_rssi); + printf("\ttxbuf:\t%u\tus\n", _rstatus.txbuf); + printf("\tnoise:\t%d\tus\n", _rstatus.noise); + printf("\tremote noise:\t%u\tus\n", _rstatus.remote_noise); + printf("\trx errors:\t%u\tus\n", _rstatus.rxerrors); + printf("\tfixed:\t%u\tus\n", _rstatus.fixed); + } } int @@ -1752,8 +1797,8 @@ int mavlink_main(int argc, char *argv[]) } else if (!strcmp(argv[1], "stop-all")) { return Mavlink::destroy_all_instances(); - // } else if (!strcmp(argv[1], "status")) { - // mavlink::g_mavlink->status(); + } else if (!strcmp(argv[1], "status")) { + return Mavlink::get_status_all_instances(); } else if (!strcmp(argv[1], "stream")) { return Mavlink::stream_command(argc, argv); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index adca0e88f..d51120462 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -51,6 +51,7 @@ #include #include #include +#include #include "mavlink_bridge_header.h" #include "mavlink_orb_subscription.h" @@ -97,6 +98,8 @@ public: static int destroy_all_instances(); + static int get_status_all_instances(); + static bool instance_exists(const char *device_name, Mavlink *self); static void forward_message(const mavlink_message_t *msg, Mavlink *self); @@ -229,6 +232,11 @@ public: */ void count_txerr(); + /** + * Get the receive status of this MAVLink link + */ + struct telemetry_status_s& get_rx_status() { return _rstatus; } + protected: Mavlink *next; @@ -285,6 +293,8 @@ private: bool _flow_control_enabled; + struct telemetry_status_s _rstatus; ///< receive status + struct mavlink_message_buffer { int write_ptr; int read_ptr; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 3ee7ec34d..528c8b72a 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -400,8 +400,7 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) mavlink_radio_status_t rstatus; mavlink_msg_radio_status_decode(msg, &rstatus); - struct telemetry_status_s tstatus; - memset(&tstatus, 0, sizeof(tstatus)); + struct telemetry_status_s &tstatus = _mavlink->get_rx_status(); tstatus.timestamp = hrt_absolute_time(); tstatus.heartbeat_time = _telemetry_heartbeat_time; -- cgit v1.2.3 From 87cc7a81ff8b3bdc9cc5a5b4fca91f8d08988774 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 15:08:56 +0200 Subject: Support force fail in valid filter --- src/modules/px4iofirmware/registers.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index b37259997..fcd53f1f1 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -189,7 +189,8 @@ volatile uint16_t r_page_setup[] = PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM | \ PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE | \ PX4IO_P_SETUP_ARMING_RC_HANDLING_DISABLED | \ - PX4IO_P_SETUP_ARMING_LOCKDOWN) + PX4IO_P_SETUP_ARMING_LOCKDOWN | \ + PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) #define PX4IO_P_SETUP_RATES_VALID ((1 << PX4IO_SERVO_COUNT) - 1) #define PX4IO_P_SETUP_RELAYS_VALID ((1 << PX4IO_RELAY_CHANNELS) - 1) -- cgit v1.2.3 From f3fe9c2fdf7a5d54cbd647551ab03211e3e64458 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 15:09:07 +0200 Subject: Print force fail status --- src/drivers/px4io/px4io.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index f5ff6e55e..c6ee08fbe 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -2002,7 +2002,7 @@ PX4IO::print_status(bool extended_status) ((features & PX4IO_P_SETUP_FEATURES_ADC_RSSI) ? " RSSI_ADC" : "") ); uint16_t arming = io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_ARMING); - printf("arming 0x%04x%s%s%s%s%s%s%s\n", + printf("arming 0x%04x%s%s%s%s%s%s%s%s\n", arming, ((arming & PX4IO_P_SETUP_ARMING_FMU_ARMED) ? " FMU_ARMED" : " FMU_DISARMED"), ((arming & PX4IO_P_SETUP_ARMING_IO_ARM_OK) ? " IO_ARM_OK" : " IO_ARM_DENIED"), @@ -2010,7 +2010,9 @@ PX4IO::print_status(bool extended_status) ((arming & PX4IO_P_SETUP_ARMING_FAILSAFE_CUSTOM) ? " FAILSAFE_CUSTOM" : ""), ((arming & PX4IO_P_SETUP_ARMING_INAIR_RESTART_OK) ? " INAIR_RESTART_OK" : ""), ((arming & PX4IO_P_SETUP_ARMING_ALWAYS_PWM_ENABLE) ? " ALWAYS_PWM_ENABLE" : ""), - ((arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) ? " LOCKDOWN" : "")); + ((arming & PX4IO_P_SETUP_ARMING_LOCKDOWN) ? " LOCKDOWN" : ""), + ((arming & PX4IO_P_SETUP_ARMING_FORCE_FAILSAFE) ? " FORCE_FAILSAFE" : "") + ); #ifdef CONFIG_ARCH_BOARD_PX4FMU_V1 printf("rates 0x%04x default %u alt %u relays 0x%04x\n", io_reg_get(PX4IO_PAGE_SETUP, PX4IO_P_SETUP_PWM_RATES), -- cgit v1.2.3 From f3ec1cd580a7a06699caba5d99b785f56316d1c2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 15:10:20 +0200 Subject: pwm command: Add missing exit 0 status --- src/systemcmds/pwm/pwm.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index 77d8ef8db..742f45484 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -649,7 +649,7 @@ pwm_main(int argc, char *argv[]) ret = ioctl(fd, PWM_SERVO_SET_FORCE_FAILSAFE, 0); } } - + exit(0); } usage("specify arm|disarm|rate|failsafe|disarmed|min|max|test|info"); -- cgit v1.2.3 From fd5065535435f9f3fa3c32b620db471f905072c2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 15:15:10 +0200 Subject: add missing hint to pwm usage --- src/systemcmds/pwm/pwm.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index 403567cb4..87c7fc647 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -652,7 +652,7 @@ pwm_main(int argc, char *argv[]) exit(0); } - usage("specify arm|disarm|rate|failsafe|disarmed|min|max|test|info"); + usage("specify arm|disarm|rate|failsafe|disarmed|min|max|test|info|forcefail"); return 0; } -- cgit v1.2.3 From 74f31618f2ca4119350372d120988c009d67064e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 15:21:29 +0200 Subject: report error in pwm command if any --- src/systemcmds/pwm/pwm.c | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/systemcmds/pwm/pwm.c b/src/systemcmds/pwm/pwm.c index 87c7fc647..c8d698b86 100644 --- a/src/systemcmds/pwm/pwm.c +++ b/src/systemcmds/pwm/pwm.c @@ -648,6 +648,10 @@ pwm_main(int argc, char *argv[]) /* force failsafe */ ret = ioctl(fd, PWM_SERVO_SET_FORCE_FAILSAFE, 0); } + + if (ret != OK) { + warnx("FAILED setting forcefail %s", argv[2]); + } } exit(0); } -- cgit v1.2.3 From ed31d6a59a21753e326ba03933ce0eb962b8412a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 15:56:37 +0200 Subject: Cleanup of heartbeat handling and status printing. Ready to go mainline --- src/modules/mavlink/mavlink_main.cpp | 32 +++++++++++++++++------------- src/modules/mavlink/mavlink_receiver.cpp | 20 +++++++++++-------- src/modules/mavlink/mavlink_receiver.h | 1 - src/modules/uORB/topics/telemetry_status.h | 3 ++- 4 files changed, 32 insertions(+), 24 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index e25851c7d..0e8f17c77 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -432,11 +432,9 @@ Mavlink::get_status_all_instances() unsigned iterations = 0; - warnx("waiting for instances to stop"); - while (inst != nullptr) { - printf("instance #%u:\n", iterations); + printf("\ninstance #%u:\n", iterations); inst->display_status(); /* move on */ @@ -1688,27 +1686,33 @@ Mavlink::start(int argc, char *argv[]) void Mavlink::display_status() { - warnx("running"); + + if (_rstatus.heartbeat_time > 0) { + printf("\theartbeat:\t%llu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time)); + } if (_rstatus.timestamp > 0) { - printf("\ttime:\t%llu\tus\n", _rstatus.heartbeat_time); + + printf("\ttype:\t\t"); switch (_rstatus.type) { case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: - printf("\t3DR RADIO\n"); + printf("3DR RADIO\n"); break; default: - printf("\tUNKNOWN RADIO\n"); + printf("UNKNOWN RADIO\n"); break; } - printf("\trssi:\t%d\t\n", _rstatus.rssi); - printf("\tremote rssi:\t%u\tus\n", _rstatus.remote_rssi); - printf("\ttxbuf:\t%u\tus\n", _rstatus.txbuf); - printf("\tnoise:\t%d\tus\n", _rstatus.noise); - printf("\tremote noise:\t%u\tus\n", _rstatus.remote_noise); - printf("\trx errors:\t%u\tus\n", _rstatus.rxerrors); - printf("\tfixed:\t%u\tus\n", _rstatus.fixed); + printf("\trssi:\t\t%d\n", _rstatus.rssi); + printf("\tremote rssi:\t%u\n", _rstatus.remote_rssi); + printf("\ttxbuf:\t\t%u\n", _rstatus.txbuf); + printf("\tnoise:\t\t%d\n", _rstatus.noise); + printf("\tremote noise:\t%u\n", _rstatus.remote_noise); + printf("\trx errors:\t%u\n", _rstatus.rxerrors); + printf("\tfixed:\t\t%u\n", _rstatus.fixed); + } else { + printf("\tno telem status.\n"); } } diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 528c8b72a..454d730d8 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -111,7 +111,6 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) : _telemetry_status_pub(-1), _rc_pub(-1), _manual_pub(-1), - _telemetry_heartbeat_time(0), _radio_status_available(false), _control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))), _hil_frames(0), @@ -403,7 +402,8 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) struct telemetry_status_s &tstatus = _mavlink->get_rx_status(); tstatus.timestamp = hrt_absolute_time(); - tstatus.heartbeat_time = _telemetry_heartbeat_time; + tstatus.telem_time = tstatus.timestamp; + /* tstatus.heartbeat_time is set by system heartbeats */ tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO; tstatus.rssi = rstatus.rssi; tstatus.remote_rssi = rstatus.remrssi; @@ -460,16 +460,20 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) /* ignore own heartbeats, accept only heartbeats from GCS */ if (msg->sysid != mavlink_system.sysid && hb.type == MAV_TYPE_GCS) { - _telemetry_heartbeat_time = hrt_absolute_time(); + + struct telemetry_status_s &tstatus = _mavlink->get_rx_status(); + + hrt_abstime tnow = hrt_absolute_time(); + + /* always set heartbeat, publish only if telemetry link not up */ + tstatus.heartbeat_time = tnow; /* if no radio status messages arrive, lets at least publish that heartbeats were received */ if (!_radio_status_available) { - struct telemetry_status_s tstatus; - memset(&tstatus, 0, sizeof(tstatus)); - - tstatus.timestamp = _telemetry_heartbeat_time; - tstatus.heartbeat_time = _telemetry_heartbeat_time; + tstatus.timestamp = tnow; + /* telem_time indicates the timestamp of a telemetry status packet and we got none */ + tstatus.telem_time = 0; tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC; if (_telemetry_status_pub < 0) { diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index b64a060e3..f4d0c52d8 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -148,7 +148,6 @@ private: orb_advert_t _telemetry_status_pub; orb_advert_t _rc_pub; orb_advert_t _manual_pub; - hrt_abstime _telemetry_heartbeat_time; bool _radio_status_available; int _control_mode_sub; int _hil_frames; diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h index 3347724a5..1297c1a9d 100644 --- a/src/modules/uORB/topics/telemetry_status.h +++ b/src/modules/uORB/topics/telemetry_status.h @@ -57,7 +57,8 @@ enum TELEMETRY_STATUS_RADIO_TYPE { struct telemetry_status_s { uint64_t timestamp; - uint64_t heartbeat_time; /**< Time of last received heartbeat from remote system */ + uint64_t heartbeat_time; /**< Time of last received heartbeat from remote system */ + uint64_t telem_time; /**< Time of last received telemetry status packet, 0 for none */ enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */ uint8_t rssi; /**< local signal strength */ uint8_t remote_rssi; /**< remote signal strength */ -- cgit v1.2.3 From 5ace06f3b820d43bc313347f3d23b121a36fbef1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 15:57:42 +0200 Subject: Add hint that heartbeats are only considered if coming from a GCS --- src/modules/mavlink/mavlink_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 0e8f17c77..7bd2b9754 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1688,7 +1688,7 @@ Mavlink::display_status() { if (_rstatus.heartbeat_time > 0) { - printf("\theartbeat:\t%llu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time)); + printf("\tGCS heartbeat:\t%llu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time)); } if (_rstatus.timestamp > 0) { -- cgit v1.2.3 From 6e3ebd3a36ce8bf3a9132b76986074ad8d9fcf35 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 16:00:37 +0200 Subject: Fix code style, no actual code edits --- src/modules/mavlink/mavlink_main.cpp | 170 +++++++++++++++++++---------------- 1 file changed, 94 insertions(+), 76 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 7bd2b9754..cb8c298c0 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -81,7 +81,7 @@ #include "mavlink_commands.h" #ifndef MAVLINK_CRC_EXTRA - #error MAVLINK_CRC_EXTRA has to be defined on PX4 systems +#error MAVLINK_CRC_EXTRA has to be defined on PX4 systems #endif /* oddly, ERROR is not defined for c++ */ @@ -154,7 +154,8 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length instance = Mavlink::get_instance(6); break; #endif - default: + + default: return; } @@ -169,17 +170,16 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length int buf_free = 0; if (instance->get_flow_control_enabled() - && ioctl(uart, FIONWRITE, (unsigned long)&buf_free) == 0) { + && ioctl(uart, FIONWRITE, (unsigned long)&buf_free) == 0) { /* Disable hardware flow control: * if no successful write since a defined time * and if the last try was not the last successful write */ if (last_write_try_times[(unsigned)channel] != 0 && - hrt_elapsed_time(&last_write_success_times[(unsigned)channel]) > 500 * 1000UL && - last_write_success_times[(unsigned)channel] != - last_write_try_times[(unsigned)channel]) - { + hrt_elapsed_time(&last_write_success_times[(unsigned)channel]) > 500 * 1000UL && + last_write_success_times[(unsigned)channel] != + last_write_try_times[(unsigned)channel]) { warnx("DISABLING HARDWARE FLOW CONTROL"); instance->enable_flow_control(false); } @@ -202,8 +202,10 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length } ssize_t ret = write(uart, ch, desired); + if (ret != desired) { instance->count_txerr(); + } else { last_write_success_times[(unsigned)channel] = last_write_try_times[(unsigned)channel]; } @@ -232,33 +234,33 @@ Mavlink::Mavlink() : _mission_result_sub(-1), _mode(MAVLINK_MODE_NORMAL), _channel(MAVLINK_COMM_0), - _logbuffer{}, - _total_counter(0), - _receive_thread{}, - _verbose(false), - _forwarding_on(false), - _passing_on(false), - _ftp_on(false), - _uart_fd(-1), - _baudrate(57600), - _datarate(10000), - _mavlink_param_queue_index(0), - mavlink_link_termination_allowed(false), - _subscribe_to_stream(nullptr), - _subscribe_to_stream_rate(0.0f), - _flow_control_enabled(true), - _rstatus{}, - _message_buffer{}, - _message_buffer_mutex{}, - _param_initialized(false), - _param_system_id(0), - _param_component_id(0), - _param_system_type(0), - _param_use_hil_gps(0), - -/* performance counters */ - _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")), - _txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe")) + _logbuffer {}, + _total_counter(0), + _receive_thread {}, + _verbose(false), + _forwarding_on(false), + _passing_on(false), + _ftp_on(false), + _uart_fd(-1), + _baudrate(57600), + _datarate(10000), + _mavlink_param_queue_index(0), + mavlink_link_termination_allowed(false), + _subscribe_to_stream(nullptr), + _subscribe_to_stream_rate(0.0f), + _flow_control_enabled(true), + _rstatus {}, + _message_buffer {}, + _message_buffer_mutex {}, + _param_initialized(false), + _param_system_id(0), + _param_component_id(0), + _param_system_type(0), + _param_use_hil_gps(0), + + /* performance counters */ + _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")), + _txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe")) { fops.ioctl = (int (*)(file *, int, long unsigned int))&mavlink_dev_ioctl; @@ -637,7 +639,8 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios * case 921600: speed = B921600; break; default: - warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\t9600, 19200, 38400, 57600\t\n115200\n230400\n460800\n921600\n", baud); + warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\t9600, 19200, 38400, 57600\t\n115200\n230400\n460800\n921600\n", + baud); return -EINVAL; } @@ -867,8 +870,9 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { mavlink_param_request_list_t req; mavlink_msg_param_request_list_decode(msg, &req); + if (req.target_system == mavlink_system.sysid && - (req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) { + (req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) { /* Start sending parameters */ mavlink_pm_start_queued_send(); send_statustext_info("[pm] sending list"); @@ -883,7 +887,9 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav mavlink_param_set_t mavlink_param_set; mavlink_msg_param_set_decode(msg, &mavlink_param_set); - if (mavlink_param_set.target_system == mavlink_system.sysid && ((mavlink_param_set.target_component == mavlink_system.compid) || (mavlink_param_set.target_component == MAV_COMP_ID_ALL))) { + if (mavlink_param_set.target_system == mavlink_system.sysid + && ((mavlink_param_set.target_component == mavlink_system.compid) + || (mavlink_param_set.target_component == MAV_COMP_ID_ALL))) { /* local name buffer to enforce null-terminated string */ char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; strncpy(name, mavlink_param_set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); @@ -910,7 +916,9 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav mavlink_param_request_read_t mavlink_param_request_read; mavlink_msg_param_request_read_decode(msg, &mavlink_param_request_read); - if (mavlink_param_request_read.target_system == mavlink_system.sysid && ((mavlink_param_request_read.target_component == mavlink_system.compid) || (mavlink_param_request_read.target_component == MAV_COMP_ID_ALL))) { + if (mavlink_param_request_read.target_system == mavlink_system.sysid + && ((mavlink_param_request_read.target_component == mavlink_system.compid) + || (mavlink_param_request_read.target_component == MAV_COMP_ID_ALL))) { /* when no index is given, loop through string ids and compare them */ if (mavlink_param_request_read.param_index == -1) { /* local name buffer to enforce null-terminated string */ @@ -973,15 +981,17 @@ Mavlink::send_statustext(unsigned severity, const char *string) /* Map severity */ switch (severity) { - case MAVLINK_IOC_SEND_TEXT_INFO: - statustext.severity = MAV_SEVERITY_INFO; - break; - case MAVLINK_IOC_SEND_TEXT_CRITICAL: - statustext.severity = MAV_SEVERITY_CRITICAL; - break; - case MAVLINK_IOC_SEND_TEXT_EMERGENCY: - statustext.severity = MAV_SEVERITY_EMERGENCY; - break; + case MAVLINK_IOC_SEND_TEXT_INFO: + statustext.severity = MAV_SEVERITY_INFO; + break; + + case MAVLINK_IOC_SEND_TEXT_CRITICAL: + statustext.severity = MAV_SEVERITY_CRITICAL; + break; + + case MAVLINK_IOC_SEND_TEXT_EMERGENCY: + statustext.severity = MAV_SEVERITY_EMERGENCY; + break; } mavlink_msg_statustext_send(_channel, statustext.severity, statustext.text); @@ -1098,12 +1108,14 @@ Mavlink::message_buffer_init(int size) _message_buffer.size = size; _message_buffer.write_ptr = 0; _message_buffer.read_ptr = 0; - _message_buffer.data = (char*)malloc(_message_buffer.size); + _message_buffer.data = (char *)malloc(_message_buffer.size); int ret; + if (_message_buffer.data == 0) { ret = ERROR; _message_buffer.size = 0; + } else { ret = OK; } @@ -1475,7 +1487,8 @@ Mavlink::task_main(int argc, char *argv[]) if (_subscribe_to_stream != nullptr) { if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) { if (_subscribe_to_stream_rate > 0.0f) { - warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, (double)_subscribe_to_stream_rate); + warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, + (double)_subscribe_to_stream_rate); } else { warnx("stream %s on device %s disabled", _subscribe_to_stream, _device_name); @@ -1514,45 +1527,46 @@ Mavlink::task_main(int argc, char *argv[]) bool is_part; uint8_t *read_ptr; - uint8_t *write_ptr; + uint8_t *write_ptr; pthread_mutex_lock(&_message_buffer_mutex); - int available = message_buffer_get_ptr((void**)&read_ptr, &is_part); + int available = message_buffer_get_ptr((void **)&read_ptr, &is_part); pthread_mutex_unlock(&_message_buffer_mutex); if (available > 0) { - // Reconstruct message from buffer + // Reconstruct message from buffer mavlink_message_t msg; - write_ptr = (uint8_t*)&msg; - - // Pull a single message from the buffer - size_t read_count = available; - if (read_count > sizeof(mavlink_message_t)) { - read_count = sizeof(mavlink_message_t); - } - - memcpy(write_ptr, read_ptr, read_count); - - // We hold the mutex until after we complete the second part of the buffer. If we don't - // we may end up breaking the empty slot overflow detection semantics when we mark the - // possibly partial read below. - pthread_mutex_lock(&_message_buffer_mutex); - + write_ptr = (uint8_t *)&msg; + + // Pull a single message from the buffer + size_t read_count = available; + + if (read_count > sizeof(mavlink_message_t)) { + read_count = sizeof(mavlink_message_t); + } + + memcpy(write_ptr, read_ptr, read_count); + + // We hold the mutex until after we complete the second part of the buffer. If we don't + // we may end up breaking the empty slot overflow detection semantics when we mark the + // possibly partial read below. + pthread_mutex_lock(&_message_buffer_mutex); + message_buffer_mark_read(read_count); /* write second part of buffer if there is some */ if (is_part && read_count < sizeof(mavlink_message_t)) { - write_ptr += read_count; - available = message_buffer_get_ptr((void**)&read_ptr, &is_part); - read_count = sizeof(mavlink_message_t) - read_count; - memcpy(write_ptr, read_ptr, read_count); + write_ptr += read_count; + available = message_buffer_get_ptr((void **)&read_ptr, &is_part); + read_count = sizeof(mavlink_message_t) - read_count; + memcpy(write_ptr, read_ptr, read_count); message_buffer_mark_read(available); } - - pthread_mutex_unlock(&_message_buffer_mutex); - _mavlink_resend_uart(_channel, &msg); + pthread_mutex_unlock(&_message_buffer_mutex); + + _mavlink_resend_uart(_channel, &msg); } } @@ -1606,6 +1620,7 @@ Mavlink::task_main(int argc, char *argv[]) message_buffer_destroy(); pthread_mutex_destroy(&_message_buffer_mutex); } + /* destroy log buffer */ mavlink_logbuffer_destroy(&_logbuffer); @@ -1627,6 +1642,7 @@ int Mavlink::start_helper(int argc, char *argv[]) /* out of memory */ res = -ENOMEM; warnx("OUT OF MEM"); + } else { /* this will actually only return once MAVLink exits */ res = instance->task_main(argc, argv); @@ -1696,10 +1712,11 @@ Mavlink::display_status() printf("\ttype:\t\t"); switch (_rstatus.type) { - case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: + case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: printf("3DR RADIO\n"); break; - default: + + default: printf("UNKNOWN RADIO\n"); break; } @@ -1711,6 +1728,7 @@ Mavlink::display_status() printf("\tremote noise:\t%u\n", _rstatus.remote_noise); printf("\trx errors:\t%u\n", _rstatus.rxerrors); printf("\tfixed:\t\t%u\n", _rstatus.fixed); + } else { printf("\tno telem status.\n"); } -- cgit v1.2.3 From 52a9513e64dacf1004fd0e11df3daf5eb607b0f2 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 16:22:02 +0200 Subject: Update rates --- src/modules/mavlink/mavlink_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index cb8c298c0..2e3a9ca33 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1454,7 +1454,7 @@ Mavlink::task_main(int argc, char *argv[]) /* don't send parameters on startup without request */ _mavlink_param_queue_index = param_count(); - MavlinkRateLimiter fast_rate_limiter(30000.0f / rate_mult); + MavlinkRateLimiter fast_rate_limiter(35000.0f / rate_mult); /* set main loop delay depending on data rate to minimize CPU overhead */ _main_loop_delay = MAIN_LOOP_DELAY / rate_mult; -- cgit v1.2.3 From 41003a243793e465a71e9b142e7c9aac132d3923 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 19 Jul 2014 17:37:13 +0200 Subject: mavlink: TX/RX rate counters added --- src/modules/mavlink/mavlink_main.cpp | 28 ++++++++++++++++++++++++++++ src/modules/mavlink/mavlink_main.h | 23 +++++++++++++++++++++++ src/modules/mavlink/mavlink_receiver.cpp | 3 +++ 3 files changed, 54 insertions(+) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 2e3a9ca33..ea60bb226 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -197,6 +197,7 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length if (buf_free < desired) { /* we don't want to send anything just in half, so return */ instance->count_txerr(); + instance->count_txerrbytes(desired); return; } } @@ -205,9 +206,11 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length if (ret != desired) { instance->count_txerr(); + instance->count_txerrbytes(desired); } else { last_write_success_times[(unsigned)channel] = last_write_try_times[(unsigned)channel]; + instance->count_txbytes(desired); } } } @@ -249,6 +252,13 @@ Mavlink::Mavlink() : _subscribe_to_stream(nullptr), _subscribe_to_stream_rate(0.0f), _flow_control_enabled(true), + _bytes_tx(0), + _bytes_txerr(0), + _bytes_rx(0), + _bytes_timestamp(0), + _rate_tx(0.0f), + _rate_txerr(0.0f), + _rate_rx(0.0f), _rstatus {}, _message_buffer {}, _message_buffer_mutex {}, @@ -1570,6 +1580,20 @@ Mavlink::task_main(int argc, char *argv[]) } } + /* update TX/RX rates*/ + if (t > _bytes_timestamp + 1000000) { + if (_bytes_timestamp != 0) { + float dt = (t - _bytes_timestamp) / 1000.0f; + _rate_tx = _bytes_tx / dt; + _rate_txerr = _bytes_txerr / dt; + _rate_rx = _bytes_rx / dt; + _bytes_tx = 0; + _bytes_txerr = 0; + _bytes_rx = 0; + } + _bytes_timestamp = t; + } + perf_end(_loop_perf); } @@ -1732,6 +1756,10 @@ Mavlink::display_status() } else { printf("\tno telem status.\n"); } + printf("\trates:\n"); + printf("\ttx: %.3f kB/s\n", (double)_rate_tx); + printf("\ttxerr: %.3f kB/s\n", (double)_rate_txerr); + printf("\trx: %.3f kB/s\n", (double)_rate_rx); } int diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index d51120462..70d13acb0 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -232,6 +232,21 @@ public: */ void count_txerr(); + /** + * Count transmitted bytes + */ + void count_txbytes(unsigned n) { _bytes_tx += n; }; + + /** + * Count bytes not transmitted because of errors + */ + void count_txerrbytes(unsigned n) { _bytes_txerr += n; }; + + /** + * Count received bytes + */ + void count_rxbytes(unsigned n) { _bytes_rx += n; }; + /** * Get the receive status of this MAVLink link */ @@ -293,6 +308,14 @@ private: bool _flow_control_enabled; + unsigned _bytes_tx; + unsigned _bytes_txerr; + unsigned _bytes_rx; + uint64_t _bytes_timestamp; + float _rate_tx; + float _rate_txerr; + float _rate_rx; + struct telemetry_status_s _rstatus; ///< receive status struct mavlink_message_buffer { diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 454d730d8..54c412ce7 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -958,6 +958,9 @@ MavlinkReceiver::receive_thread(void *arg) _mavlink->handle_message(&msg); } } + + /* count received bytes */ + _mavlink->count_rxbytes(nread); } } -- cgit v1.2.3 From 5d2489880c2a42bc67554efa7715ba3a761c5d17 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 21:14:14 +0200 Subject: Fix low voltage warning threshold to 9%, not 90% --- src/modules/commander/commander.cpp | 2 +- src/modules/commander/commander_params.c | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index cb447f8ce..562e9a1b6 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1282,7 +1282,7 @@ int commander_thread_main(int argc, char *argv[]) status.battery_warning = VEHICLE_BATTERY_WARNING_LOW; status_changed = true; - } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.9f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) { + } else if (status.condition_battery_voltage_valid && status.battery_remaining < 0.09f && !critical_battery_voltage_actions_done && low_battery_voltage_actions_done) { /* critical battery voltage, this is rather an emergency, change state machine */ critical_battery_voltage_actions_done = true; mavlink_log_emergency(mavlink_fd, "CRITICAL BATTERY, LAND IMMEDIATELY"); diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 448bc53cd..a09e2d6bf 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -56,7 +56,7 @@ PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f); * * @group Battery Calibration */ -PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.3f); +PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f); /** * Full cell voltage. -- cgit v1.2.3 From e7d8d9c91fe72169d292a5e0ac44133a218f27a0 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 19 Jul 2014 23:19:49 +0200 Subject: position_estimator_inav: parameters descriptions added --- .../position_estimator_inav_params.c | 174 +++++++++++++++++++++ 1 file changed, 174 insertions(+) diff --git a/src/modules/position_estimator_inav/position_estimator_inav_params.c b/src/modules/position_estimator_inav/position_estimator_inav_params.c index 0581f8236..98b31d17b 100644 --- a/src/modules/position_estimator_inav/position_estimator_inav_params.c +++ b/src/modules/position_estimator_inav/position_estimator_inav_params.c @@ -40,22 +40,196 @@ #include "position_estimator_inav_params.h" +/** + * Z axis weight for barometer + * + * Weight (cutoff frequency) for barometer altitude measurements. + * + * @min 0.0 + * @max 10.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_W_Z_BARO, 0.5f); + +/** + * Z axis weight for GPS + * + * Weight (cutoff frequency) for GPS altitude measurements. GPS altitude data is very noisy and should be used only as slow correction for baro offset. + * + * @min 0.0 + * @max 10.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_W_Z_GPS_P, 0.005f); + +/** + * Z axis weight for sonar + * + * Weight (cutoff frequency) for sonar measurements. + * + * @min 0.0 + * @max 10.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_W_Z_SONAR, 3.0f); + +/** + * XY axis weight for GPS position + * + * Weight (cutoff frequency) for GPS position measurements. + * + * @min 0.0 + * @max 10.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_P, 1.0f); + +/** + * XY axis weight for GPS velocity + * + * Weight (cutoff frequency) for GPS velocity measurements. + * + * @min 0.0 + * @max 10.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_W_XY_GPS_V, 2.0f); + +/** + * XY axis weight for optical flow + * + * Weight (cutoff frequency) for optical flow (velocity) measurements. + * + * @min 0.0 + * @max 10.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_W_XY_FLOW, 5.0f); + +/** + * XY axis weight for resetting velocity + * + * When velocity sources lost slowly decrease estimated horizontal velocity with this weight. + * + * @min 0.0 + * @max 10.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_W_XY_RES_V, 0.5f); + +/** + * XY axis weight factor for GPS when optical flow available + * + * When optical flow data available, multiply GPS weights (for position and velocity) by this factor. + * + * @min 0.0 + * @max 1.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_W_GPS_FLOW, 0.1f); + +/** + * Accelerometer bias estimation weight + * + * Weight (cutoff frequency) for accelerometer bias estimation. 0 to disable. + * + * @min 0.0 + * @max 0.1 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_W_ACC_BIAS, 0.05f); + +/** + * Optical flow scale factor + * + * Factor to convert raw optical flow (in pixels) to radians [rad/px]. + * + * @min 0.0 + * @max 1.0 + * @unit rad/px + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_FLOW_K, 0.15f); + +/** + * Minimal acceptable optical flow quality + * + * 0 - lowest quality, 1 - best quality. + * + * @min 0.0 + * @max 1.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_FLOW_Q_MIN, 0.5f); + +/** + * Weight for sonar filter + * + * Sonar filter detects spikes on sonar measurements and used to detect new surface level. + * + * @min 0.0 + * @max 1.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_SONAR_FILT, 0.05f); + +/** + * Sonar maximal error for new surface + * + * If sonar measurement error is larger than this value it skiped (spike) or accepted as new surface level (if offset is stable). + * + * @min 0.0 + * @max 1.0 + * @unit m + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_SONAR_ERR, 0.5f); + +/** + * Land detector time + * + * Vehicle assumed landed if no altitude changes happened during this time on low throttle. + * + * @min 0.0 + * @max 10.0 + * @unit s + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_LAND_T, 3.0f); + +/** + * Land detector altitude dispersion threshold + * + * Dispersion threshold for triggering land detector. + * + * @min 0.0 + * @max 10.0 + * @unit m + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_LAND_DISP, 0.7f); + +/** + * Land detector throttle threshold + * + * Value should be lower than minimal hovering thrust. Half of it is good choice. + * + * @min 0.0 + * @max 1.0 + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_LAND_THR, 0.2f); + +/** + * GPS delay + * + * GPS delay compensation + * + * @min 0.0 + * @max 1.0 + * @unit s + * @group Position Estimator INAV + */ PARAM_DEFINE_FLOAT(INAV_DELAY_GPS, 0.2f); int parameters_init(struct position_estimator_inav_param_handles *h) -- cgit v1.2.3 From cd8a0cd21771fb3a6fb8cddfc3da322eb04f10db Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 23:39:02 +0200 Subject: mavlink: Only send event-based messages if there is space in the buffer --- src/modules/mavlink/mavlink_main.cpp | 60 +++++++++++++++++++++++++++++++++--- src/modules/mavlink/mavlink_main.h | 17 +++++++++- src/modules/mavlink/mavlink_stream.h | 13 ++++++++ 3 files changed, 84 insertions(+), 6 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index ea60bb226..e6b558ca6 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -246,7 +246,8 @@ Mavlink::Mavlink() : _ftp_on(false), _uart_fd(-1), _baudrate(57600), - _datarate(10000), + _datarate(1000), + _datarate_events(500), _mavlink_param_queue_index(0), mavlink_link_termination_allowed(false), _subscribe_to_stream(nullptr), @@ -352,6 +353,18 @@ Mavlink::count_txerr() perf_count(_txerr_perf); } +unsigned +Mavlink::get_free_tx_buf() +{ + unsigned buf_free; + + if (!ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free)) { + return buf_free; + } else { + return 0; + } +} + void Mavlink::set_mode(enum MAVLINK_MODE mode) { @@ -1083,6 +1096,31 @@ Mavlink::configure_stream(const char *stream_name, const float rate) return ERROR; } +void +Mavlink::adjust_stream_rates(const float multiplier) +{ + /* do not allow to push us to zero */ + if (multiplier < 0.01f) { + return; + } + + /* search if stream exists */ + MavlinkStream *stream; + LL_FOREACH(_streams, stream) { + /* set new interval */ + unsigned interval = stream->get_interval(); + interval /= multiplier; + + /* allow max ~600 Hz */ + if (interval < 1600) { + interval = 1600; + } + + /* set new interval */ + stream->set_interval(interval * multiplier); + } +} + void Mavlink::configure_stream_threadsafe(const char *stream_name, const float rate) { @@ -1464,7 +1502,7 @@ Mavlink::task_main(int argc, char *argv[]) /* don't send parameters on startup without request */ _mavlink_param_queue_index = param_count(); - MavlinkRateLimiter fast_rate_limiter(35000.0f / rate_mult); + MavlinkRateLimiter fast_rate_limiter(30000.0f / rate_mult); /* set main loop delay depending on data rate to minimize CPU overhead */ _main_loop_delay = MAIN_LOOP_DELAY / rate_mult; @@ -1519,10 +1557,22 @@ Mavlink::task_main(int argc, char *argv[]) } if (fast_rate_limiter.check(t)) { - mavlink_pm_queued_send(); - _mission_manager->eventloop(); - if (!mavlink_logbuffer_is_empty(&_logbuffer)) { + unsigned buf_free = get_free_tx_buf(); + + /* only send messages if they fit the buffer */ + if (buf_free >= (MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { + mavlink_pm_queued_send(); + } + + buf_free = get_free_tx_buf(); + if (buf_free >= (MAVLINK_MSG_ID_MISSION_ITEM_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { + _mission_manager->eventloop(); + } + + buf_free = get_free_tx_buf(); + if (buf_free >= (MAVLINK_MSG_ID_STATUSTEXT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) && + (!mavlink_logbuffer_is_empty(&_logbuffer))) { struct mavlink_logmessage msg; int lb_ret = mavlink_logbuffer_read(&_logbuffer, &msg); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 70d13acb0..e9d6b9c86 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -247,6 +247,13 @@ public: */ void count_rxbytes(unsigned n) { _bytes_rx += n; }; + /** + * Get the free space in the transmit buffer + * + * @return free space in the UART TX buffer + */ + unsigned get_free_tx_buf(); + /** * Get the receive status of this MAVLink link */ @@ -292,7 +299,8 @@ private: bool _ftp_on; int _uart_fd; int _baudrate; - int _datarate; + int _datarate; ///< data rate for normal streams (attitude, position, etc.) + int _datarate_events; ///< data rate for params, waypoints, text messages /** * If the queue index is not at 0, the queue sending @@ -385,6 +393,13 @@ private: int configure_stream(const char *stream_name, const float rate); + /** + * Adjust the stream rates based on the current rate + * + * @param multiplier if greater than 1, the transmission rate will increase, if smaller than one decrease + */ + void adjust_stream_rates(const float multiplier); + int message_buffer_init(int size); void message_buffer_destroy(); diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h index 20e1c7c44..f539d225b 100644 --- a/src/modules/mavlink/mavlink_stream.h +++ b/src/modules/mavlink/mavlink_stream.h @@ -56,7 +56,20 @@ public: MavlinkStream(); virtual ~MavlinkStream(); + + /** + * Get the interval + * + * @param interval the inveral in microseconds (us) between messages + */ void set_interval(const unsigned int interval); + + /** + * Get the interval + * + * @return the inveral in microseconds (us) between messages + */ + unsigned get_interval() { return _interval; } void set_channel(mavlink_channel_t channel); /** -- cgit v1.2.3 From 1f3625371d787cdc452b45ad9d9a01423ae51f96 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 20 Jul 2014 10:18:00 +0200 Subject: Obey radio status in opportunistic transmissions as well. Last missing bit are adaptive rates --- src/modules/mavlink/mavlink_main.cpp | 29 ++++++++++++++++++++++++++++- 1 file changed, 28 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index e6b558ca6..e7e96dc3a 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -359,7 +359,34 @@ Mavlink::get_free_tx_buf() unsigned buf_free; if (!ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free)) { - return buf_free; + if (_rstatus.timestamp > 0 && + (hrt_elapsed_time(&_rstatus.timestamp) < (2 * 1000 * 1000))) { + + unsigned low_buf; + + switch (_rstatus.type) { + case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: + low_buf = 50; + break; + default: + low_buf = 50; + break; + } + + if (_rstatus.txbuf < low_buf) { + /* + * If the TX buf measure is initialized and up to date and low + * return 0 to slow event based transmission + */ + return 0; + } else { + /* there is no SW flow control option, just use what our buffer tells us */ + return buf_free; + } + + } else { + return buf_free; + } } else { return 0; } -- cgit v1.2.3 From 5fb2a92e7704c2e298128addf890722b6b03289a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 20 Jul 2014 14:28:05 +0200 Subject: commander: Do not confuse developers with wrong comments, do not confuse users with not at all helpful "general error" messages. --- src/modules/commander/commander.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 04450a44f..48cbc254f 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -1407,8 +1407,12 @@ int commander_thread_main(int argc, char *argv[]) arming_state_changed = true; } else if (arming_ret == TRANSITION_DENIED) { - /* DENIED here indicates bug in the commander */ - mavlink_log_critical(mavlink_fd, "arming state transition denied"); + /* + * the arming transition can be denied to a number of reasons: + * - pre-flight check failed (sensors not ok or not calibrated) + * - safety not disabled + * - system not in manual mode + */ tune_negative(true); } -- cgit v1.2.3 From b3a80025b3bf514e987d19b7292ba0f9d16d7d1d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 20 Jul 2014 14:28:24 +0200 Subject: Do not confuse operators / users with technical error messages --- src/modules/commander/state_machine_helper.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 372ba9d7d..4ca8471fc 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -216,11 +216,8 @@ arming_state_transition(struct vehicle_status_s *status, /// current } if (ret == TRANSITION_DENIED) { - static const char *errMsg = "INVAL: %s - %s"; - - mavlink_log_critical(mavlink_fd, errMsg, state_names[status->arming_state], state_names[new_arming_state]); - - warnx(errMsg, state_names[status->arming_state], state_names[new_arming_state]); + /* only print to console here as this is too technical to be useful during operation */ + warnx("INVAL: %s - %s", state_names[status->arming_state], state_names[new_arming_state]); } return ret; -- cgit v1.2.3 From f3b8890601e40e5131c55e6f96ad1452a53410eb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 20 Jul 2014 14:31:23 +0200 Subject: commander: Explain sensor arming fail case to users --- src/modules/commander/state_machine_helper.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 4ca8471fc..16ed8dd52 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -200,6 +200,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current /* Sensors need to be initialized for STANDBY state */ if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) { + mavlink_log_critical(mavlink_fd, "NOT ARMING: Sensors not operational."); valid_transition = false; } -- cgit v1.2.3 From a5f538dc5c9570b59c7135570a662651cb857698 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 20 Jul 2014 16:06:31 +0200 Subject: Commander: Print technical feedback as last resort if no feedback was provided before --- src/modules/commander/state_machine_helper.cpp | 24 +++++++++++++++++------- 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 16ed8dd52..7b26e3e8c 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -110,8 +110,8 @@ arming_state_transition(struct vehicle_status_s *status, /// current ASSERT(ARMING_STATE_IN_AIR_RESTORE == ARMING_STATE_MAX - 1); transition_result_t ret = TRANSITION_DENIED; - arming_state_t current_arming_state = status->arming_state; + bool feedback_provided = false; /* only check transition if the new state is actually different from the current one */ if (new_arming_state == current_arming_state) { @@ -156,13 +156,15 @@ arming_state_transition(struct vehicle_status_s *status, /// current // Fail transition if pre-arm check fails if (prearm_ret) { + /* the prearm check already prints the reject reason */ + feedback_provided = true; valid_transition = false; // Fail transition if we need safety switch press } else if (safety->safety_switch_available && !safety->safety_off) { - mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch!"); - + mavlink_log_critical(mavlink_fd, "NOT ARMING: Press safety switch first!"); + feedback_provided = true; valid_transition = false; } @@ -173,6 +175,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current if (!status->condition_power_input_valid) { mavlink_log_critical(mavlink_fd, "NOT ARMING: Connect power module."); + feedback_provided = true; valid_transition = false; } @@ -182,6 +185,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current (status->avionics_power_rail_voltage < 4.9f))) { mavlink_log_critical(mavlink_fd, "NOT ARMING: Avionics power low: %6.2f V.", (double)status->avionics_power_rail_voltage); + feedback_provided = true; valid_transition = false; } } @@ -201,6 +205,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current /* Sensors need to be initialized for STANDBY state */ if (new_arming_state == ARMING_STATE_STANDBY && !status->condition_system_sensors_initialized) { mavlink_log_critical(mavlink_fd, "NOT ARMING: Sensors not operational."); + feedback_provided = true; valid_transition = false; } @@ -217,8 +222,14 @@ arming_state_transition(struct vehicle_status_s *status, /// current } if (ret == TRANSITION_DENIED) { - /* only print to console here as this is too technical to be useful during operation */ - warnx("INVAL: %s - %s", state_names[status->arming_state], state_names[new_arming_state]); + const char * str = "INVAL: %s - %s"; + /* only print to console here by default as this is too technical to be useful during operation */ + warnx(str, state_names[status->arming_state], state_names[new_arming_state]); + + /* print to MAVLink if we didn't provide any feedback yet */ + if (!feedback_provided) { + mavlink_log_critical(mavlink_fd, str, state_names[status->arming_state], state_names[new_arming_state]); + } } return ret; @@ -646,8 +657,7 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) float accel_magnitude = sqrtf(acc.x * acc.x + acc.y * acc.y + acc.z * acc.z); if (accel_magnitude < 4.0f || accel_magnitude > 15.0f /* m/s^2 */) { - mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL RANGE"); - mavlink_log_critical(mavlink_fd, "hold still while arming"); + mavlink_log_critical(mavlink_fd, "ARM FAIL: ACCEL RANGE, hold still"); /* this is frickin' fatal */ failed = true; goto system_eval; -- cgit v1.2.3 From 3935540c7df0f67946b637af6dc2d3145453c326 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 20 Jul 2014 16:23:43 +0200 Subject: Set full voltage correctly to ensure percentage range fits. Force all users to new value by param renaming. Since this will tend to show batteries as more drained than before, this is a change in a safe direction and will not trigger unnoticed discharges. --- src/modules/commander/commander_helper.cpp | 6 +++--- src/modules/commander/commander_params.c | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index a4aafa1f6..239b77df0 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -289,8 +289,8 @@ float battery_remaining_estimate_voltage(float voltage, float discharged, float static param_t bat_n_cells_h; static param_t bat_capacity_h; static param_t bat_v_load_drop_h; - static float bat_v_empty = 3.2f; - static float bat_v_full = 4.0f; + static float bat_v_empty = 3.4f; + static float bat_v_full = 4.2f; static float bat_v_load_drop = 0.1f; static int bat_n_cells = 3; static float bat_capacity = -1.0f; @@ -299,7 +299,7 @@ float battery_remaining_estimate_voltage(float voltage, float discharged, float if (!initialized) { bat_v_empty_h = param_find("BAT_V_EMPTY"); - bat_v_full_h = param_find("BAT_V_FULL"); + bat_v_full_h = param_find("BAT_V_CHARGED"); bat_n_cells_h = param_find("BAT_N_CELLS"); bat_capacity_h = param_find("BAT_CAPACITY"); bat_v_load_drop_h = param_find("BAT_V_LOAD_DROP"); diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index a09e2d6bf..dea12db40 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -65,7 +65,7 @@ PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f); * * @group Battery Calibration */ -PARAM_DEFINE_FLOAT(BAT_V_FULL, 4.15f); +PARAM_DEFINE_FLOAT(BAT_V_CHARGED, 4.2f); /** * Number of cells. -- cgit v1.2.3 From 264fe884a2825ae430a19ba61e8c89d6a214f5cd Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 20 Jul 2014 16:28:44 +0200 Subject: Fixed load voltage calculation --- src/modules/commander/commander_helper.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index 239b77df0..d87af2d7d 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -317,7 +317,8 @@ float battery_remaining_estimate_voltage(float voltage, float discharged, float counter++; /* remaining charge estimate based on voltage and internal resistance (drop under load) */ - float remaining_voltage = (voltage - bat_n_cells * (bat_v_empty - (bat_v_load_drop * throttle_normalized)) / (bat_n_cells * (bat_v_full - bat_v_empty)); + float bat_v_full_dynamic = bat_v_full - (bat_v_load_drop * throttle_normalized); + float remaining_voltage = (voltage - (bat_n_cells * bat_v_empty)) / (bat_n_cells * (bat_v_full_dynamic - bat_v_empty)); if (bat_capacity > 0.0f) { /* if battery capacity is known, use discharged current for estimate, but don't show more than voltage estimate */ -- cgit v1.2.3 From c95de36d3a01bda1d3664fbc46df3a5fc35fe4da Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 20 Jul 2014 19:42:31 +0200 Subject: commander: Add missing parameter definition --- src/modules/commander/commander_helper.cpp | 2 +- src/modules/commander/commander_params.c | 10 ++++++++++ 2 files changed, 11 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/commander_helper.cpp b/src/modules/commander/commander_helper.cpp index d87af2d7d..2022e99fb 100644 --- a/src/modules/commander/commander_helper.cpp +++ b/src/modules/commander/commander_helper.cpp @@ -291,7 +291,7 @@ float battery_remaining_estimate_voltage(float voltage, float discharged, float static param_t bat_v_load_drop_h; static float bat_v_empty = 3.4f; static float bat_v_full = 4.2f; - static float bat_v_load_drop = 0.1f; + static float bat_v_load_drop = 0.06f; static int bat_n_cells = 3; static float bat_capacity = -1.0f; static bool initialized = false; diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index dea12db40..0e4973b5f 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -67,6 +67,16 @@ PARAM_DEFINE_FLOAT(BAT_V_EMPTY, 3.4f); */ PARAM_DEFINE_FLOAT(BAT_V_CHARGED, 4.2f); +/** + * Voltage drop per cell on 100% load + * + * This implicitely defines the internal resistance + * to maximum current ratio and assumes linearity. + * + * @group Battery Calibration + */ +PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.06f); + /** * Number of cells. * -- cgit v1.2.3 From ee7cd04e4c480a1931223889081074c469be0dbb Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sun, 20 Jul 2014 20:34:32 +0200 Subject: mavlink: use send_message() method of Mavlink class instead of using helpers --- src/modules/mavlink/mavlink_main.cpp | 237 +++++++++++++------------------ src/modules/mavlink/mavlink_main.h | 6 + src/modules/mavlink/mavlink_messages.cpp | 32 ++--- src/modules/mavlink/mavlink_stream.cpp | 13 +- src/modules/mavlink/mavlink_stream.h | 8 +- 5 files changed, 123 insertions(+), 173 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index e7e96dc3a..e3c452fb2 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -94,11 +94,15 @@ static const int ERROR = -1; #define MAX_DATA_RATE 10000 // max data rate in bytes/s #define MAIN_LOOP_DELAY 10000 // 100 Hz @ 1000 bytes/s data rate +#define TX_BUFFER_GAP 256 + static Mavlink *_mavlink_instances = nullptr; /* TODO: if this is a class member it crashes */ static struct file_operations fops; +static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; + /** * mavlink app start / stop handling function * @@ -108,113 +112,6 @@ extern "C" __EXPORT int mavlink_main(int argc, char *argv[]); extern mavlink_system_t mavlink_system; -static uint64_t last_write_success_times[6] = {0}; -static uint64_t last_write_try_times[6] = {0}; - -/* - * Internal function to send the bytes through the right serial port - */ -void -mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length) -{ - - Mavlink *instance; - - switch (channel) { - case MAVLINK_COMM_0: - instance = Mavlink::get_instance(0); - break; - - case MAVLINK_COMM_1: - instance = Mavlink::get_instance(1); - break; - - case MAVLINK_COMM_2: - instance = Mavlink::get_instance(2); - break; - - case MAVLINK_COMM_3: - instance = Mavlink::get_instance(3); - break; -#ifdef MAVLINK_COMM_4 - - case MAVLINK_COMM_4: - instance = Mavlink::get_instance(4); - break; -#endif -#ifdef MAVLINK_COMM_5 - - case MAVLINK_COMM_5: - instance = Mavlink::get_instance(5); - break; -#endif -#ifdef MAVLINK_COMM_6 - - case MAVLINK_COMM_6: - instance = Mavlink::get_instance(6); - break; -#endif - - default: - return; - } - - int uart = instance->get_uart_fd(); - - ssize_t desired = (sizeof(uint8_t) * length); - - /* - * Check if the OS buffer is full and disable HW - * flow control if it continues to be full - */ - int buf_free = 0; - - if (instance->get_flow_control_enabled() - && ioctl(uart, FIONWRITE, (unsigned long)&buf_free) == 0) { - - /* Disable hardware flow control: - * if no successful write since a defined time - * and if the last try was not the last successful write - */ - if (last_write_try_times[(unsigned)channel] != 0 && - hrt_elapsed_time(&last_write_success_times[(unsigned)channel]) > 500 * 1000UL && - last_write_success_times[(unsigned)channel] != - last_write_try_times[(unsigned)channel]) { - warnx("DISABLING HARDWARE FLOW CONTROL"); - instance->enable_flow_control(false); - } - - } - - /* If the wait until transmit flag is on, only transmit after we've received messages. - Otherwise, transmit all the time. */ - if (instance->should_transmit()) { - last_write_try_times[(unsigned)channel] = hrt_absolute_time(); - - /* check if there is space in the buffer, let it overflow else */ - if (!ioctl(uart, FIONWRITE, (unsigned long)&buf_free)) { - - if (buf_free < desired) { - /* we don't want to send anything just in half, so return */ - instance->count_txerr(); - instance->count_txerrbytes(desired); - return; - } - } - - ssize_t ret = write(uart, ch, desired); - - if (ret != desired) { - instance->count_txerr(); - instance->count_txerrbytes(desired); - - } else { - last_write_success_times[(unsigned)channel] = last_write_try_times[(unsigned)channel]; - instance->count_txbytes(desired); - } - } -} - static void usage(void); Mavlink::Mavlink() : @@ -253,6 +150,8 @@ Mavlink::Mavlink() : _subscribe_to_stream(nullptr), _subscribe_to_stream_rate(0.0f), _flow_control_enabled(true), + _last_write_success_time(0), + _last_write_try_time(0), _bytes_tx(0), _bytes_txerr(0), _bytes_rx(0), @@ -359,30 +258,10 @@ Mavlink::get_free_tx_buf() unsigned buf_free; if (!ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free)) { - if (_rstatus.timestamp > 0 && - (hrt_elapsed_time(&_rstatus.timestamp) < (2 * 1000 * 1000))) { - - unsigned low_buf; - - switch (_rstatus.type) { - case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: - low_buf = 50; - break; - default: - low_buf = 50; - break; - } + if (_rstatus.telem_time > 0 && + (hrt_elapsed_time(&_rstatus.telem_time) < (2 * 1000 * 1000))) { - if (_rstatus.txbuf < low_buf) { - /* - * If the TX buf measure is initialized and up to date and low - * return 0 to slow event based transmission - */ - return 0; - } else { - /* there is no SW flow control option, just use what our buffer tells us */ - return buf_free; - } + return (unsigned)(buf_free * 0.01f * _rstatus.txbuf); } else { return buf_free; @@ -808,13 +687,93 @@ Mavlink::set_hil_enabled(bool hil_enabled) return ret; } +bool +Mavlink::check_can_send(const int prio, const unsigned packet_len) +{ + /* + * Check if the OS buffer is full and disable HW + * flow control if it continues to be full + */ + int buf_free = 0; + + if (get_flow_control_enabled() + && ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free) == 0) { + + /* Disable hardware flow control: + * if no successful write since a defined time + * and if the last try was not the last successful write + */ + if (_last_write_try_time != 0 && + hrt_elapsed_time(&_last_write_success_time) > 500 * 1000UL && + _last_write_success_time != _last_write_try_time) { + warnx("DISABLING HARDWARE FLOW CONTROL"); + enable_flow_control(false); + } + } + + /* If the wait until transmit flag is on, only transmit after we've received messages. + Otherwise, transmit all the time. */ + if (should_transmit()) { + _last_write_try_time = hrt_absolute_time(); + + /* check if there is space in the buffer, let it overflow else */ + ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free); + + if (buf_free >= (prio <= 0 ? packet_len : TX_BUFFER_GAP)) { + warnx("\t\t\tSKIP %i bytes prio %i", packet_len, (int)prio); + /* we don't want to send anything just in half, so return */ + count_txerr(); + count_txerrbytes(packet_len); + return true; + } + } + return false; +} + void -Mavlink::send_message(const mavlink_message_t *msg) +Mavlink::send_message(const uint8_t msgid, const void *msg, const int prio) { uint8_t buf[MAVLINK_MAX_PACKET_LEN]; - uint16_t len = mavlink_msg_to_send_buffer(buf, msg); - mavlink_send_uart_bytes(_channel, buf, len); + uint8_t payload_len = mavlink_message_lengths[msgid]; + unsigned packet_len = payload_len + MAVLINK_NUM_NON_PAYLOAD_BYTES; + if (!check_can_send(prio, packet_len)) { + return; + } + + /* header */ + buf[0] = MAVLINK_STX; + buf[1] = payload_len; + buf[2] = mavlink_get_channel_status(_channel)->current_tx_seq++; // TODO use internal seq counter? + buf[3] = mavlink_system.sysid; + buf[4] = mavlink_system.compid; + buf[5] = msgid; + + /* payload */ + memcpy(&buf[MAVLINK_NUM_HEADER_BYTES], msg, payload_len); + + /* checksum */ + uint16_t checksum; + crc_init(&checksum); + crc_accumulate_buffer(&checksum, &buf[1], MAVLINK_CORE_HEADER_LEN + payload_len); +#if MAVLINK_CRC_EXTRA + crc_accumulate(crc_extra, &checksum); +#endif + + buf[MAVLINK_NUM_HEADER_BYTES + payload_len] = (uint8_t)(checksum & 0xFF); + buf[MAVLINK_NUM_HEADER_BYTES + payload_len + 1] = (uint8_t)(checksum >> 8); + + /* send message to UART */ + ssize_t ret = write(_uart_fd, buf, packet_len); + + if (ret != packet_len) { + count_txerr(); + count_txerrbytes(packet_len); + + } else { + _last_write_success_time = _last_write_try_time; + count_txbytes(packet_len); + } } void @@ -1585,21 +1544,17 @@ Mavlink::task_main(int argc, char *argv[]) if (fast_rate_limiter.check(t)) { - unsigned buf_free = get_free_tx_buf(); - /* only send messages if they fit the buffer */ - if (buf_free >= (MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { + if (check_can_send(0, MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { mavlink_pm_queued_send(); } - buf_free = get_free_tx_buf(); - if (buf_free >= (MAVLINK_MSG_ID_MISSION_ITEM_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { + if (check_can_send(0, MAVLINK_MSG_ID_MISSION_ITEM_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { _mission_manager->eventloop(); } - buf_free = get_free_tx_buf(); - if (buf_free >= (MAVLINK_MSG_ID_STATUSTEXT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) && - (!mavlink_logbuffer_is_empty(&_logbuffer))) { + if (!mavlink_logbuffer_is_empty(&_logbuffer) && + check_can_send(0, MAVLINK_MSG_ID_STATUSTEXT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { struct mavlink_logmessage msg; int lb_ret = mavlink_logbuffer_read(&_logbuffer, &msg); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index e9d6b9c86..1c62b03d2 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -160,6 +160,10 @@ public: */ int set_hil_enabled(bool hil_enabled); + bool check_can_send(const int prio, const unsigned packet_len); + + void send_message(const uint8_t msgid, const void *msg, const int prio); + void send_message(const mavlink_message_t *msg); void handle_message(const mavlink_message_t *msg); @@ -315,6 +319,8 @@ private: float _subscribe_to_stream_rate; bool _flow_control_enabled; + uint64_t _last_write_success_time; + uint64_t _last_write_try_time; unsigned _bytes_tx; unsigned _bytes_txerr; diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 6885bebde..fe33985d2 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -249,9 +249,9 @@ public: return MAVLINK_MSG_ID_HEARTBEAT; } - static MavlinkStream *new_instance() + static MavlinkStream *new_instance(Mavlink *mavlink) { - return new MavlinkStreamHeartbeat(); + return new MavlinkStreamHeartbeat(mavlink); } private: @@ -263,15 +263,15 @@ private: MavlinkStreamHeartbeat& operator = (const MavlinkStreamHeartbeat &); protected: - explicit MavlinkStreamHeartbeat() : MavlinkStream(), + explicit MavlinkStreamHeartbeat(Mavlink *mavlink) : MavlinkStream(mavlink), status_sub(nullptr), pos_sp_triplet_sub(nullptr) {} - void subscribe(Mavlink *mavlink) + void subscribe() { - status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); - pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); + status_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); + pos_sp_triplet_sub = _mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); } void send(const hrt_abstime t) @@ -290,17 +290,15 @@ protected: memset(&pos_sp_triplet, 0, sizeof(pos_sp_triplet)); } - uint8_t mavlink_state = 0; - uint8_t mavlink_base_mode = 0; - uint32_t mavlink_custom_mode = 0; - get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode); - - mavlink_msg_heartbeat_send(_channel, - mavlink_system.type, - MAV_AUTOPILOT_PX4, - mavlink_base_mode, - mavlink_custom_mode, - mavlink_state); + mavlink_heartbeat_t msg; + msg.base_mode = 0; + msg.custom_mode = 0; + get_mavlink_mode_state(&status, &pos_sp_triplet, &msg.system_status, &msg.base_mode, &msg.custom_mode); + msg.type = mavlink_system.type; + msg.autopilot = mavlink_system.type; + msg.mavlink_version = 3; + + _mavlink->send_message(MAVLINK_MSG_ID_HEARTBEAT, &msg, 1); } }; diff --git a/src/modules/mavlink/mavlink_stream.cpp b/src/modules/mavlink/mavlink_stream.cpp index 7279206db..79dc23cc6 100644 --- a/src/modules/mavlink/mavlink_stream.cpp +++ b/src/modules/mavlink/mavlink_stream.cpp @@ -43,9 +43,9 @@ #include "mavlink_stream.h" #include "mavlink_main.h" -MavlinkStream::MavlinkStream() : +MavlinkStream::MavlinkStream(Mavlink *mavlink) : next(nullptr), - _channel(MAVLINK_COMM_0), + _mavlink(mavlink), _interval(1000000), _last_sent(0) { @@ -64,15 +64,6 @@ MavlinkStream::set_interval(const unsigned int interval) _interval = interval; } -/** - * Set mavlink channel - */ -void -MavlinkStream::set_channel(mavlink_channel_t channel) -{ - _channel = channel; -} - /** * Update subscriptions and send message if necessary */ diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h index f539d225b..7d3afbbb5 100644 --- a/src/modules/mavlink/mavlink_stream.h +++ b/src/modules/mavlink/mavlink_stream.h @@ -54,7 +54,7 @@ class MavlinkStream public: MavlinkStream *next; - MavlinkStream(); + MavlinkStream(Mavlink *mavlink); virtual ~MavlinkStream(); /** @@ -76,14 +76,14 @@ public: * @return 0 if updated / sent, -1 if unchanged */ int update(const hrt_abstime t); - static MavlinkStream *new_instance(); + static MavlinkStream *new_instance(const Mavlink *mavlink); static const char *get_name_static(); - virtual void subscribe(Mavlink *mavlink) = 0; + virtual void subscribe() = 0; virtual const char *get_name() const = 0; virtual uint8_t get_id() = 0; protected: - mavlink_channel_t _channel; + Mavlink * _mavlink; unsigned int _interval; virtual void send(const hrt_abstime t) = 0; -- cgit v1.2.3 From 25d1cc3995f3ecafe2408582296d6dedfe49ce53 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 21 Jul 2014 07:35:23 +0200 Subject: Final value for battery load param default --- src/modules/commander/commander_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 0e4973b5f..dba68700b 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -75,7 +75,7 @@ PARAM_DEFINE_FLOAT(BAT_V_CHARGED, 4.2f); * * @group Battery Calibration */ -PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.06f); +PARAM_DEFINE_FLOAT(BAT_V_LOAD_DROP, 0.07f); /** * Number of cells. -- cgit v1.2.3 From afff12374240240ec2bbf2ba043b37cca8b3298a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 21 Jul 2014 13:30:56 +0200 Subject: Add PX4IO voltage dataset and linear fit --- Tools/tests-host/data/fit_linear_voltage.m | 14 ++++++ Tools/tests-host/data/px4io_v1.3.csv | 70 ++++++++++++++++++++++++++++++ 2 files changed, 84 insertions(+) create mode 100644 Tools/tests-host/data/fit_linear_voltage.m create mode 100644 Tools/tests-host/data/px4io_v1.3.csv diff --git a/Tools/tests-host/data/fit_linear_voltage.m b/Tools/tests-host/data/fit_linear_voltage.m new file mode 100644 index 000000000..a0384b486 --- /dev/null +++ b/Tools/tests-host/data/fit_linear_voltage.m @@ -0,0 +1,14 @@ +close all; +clear all; +M = importdata('px4io_v1.3.csv'); +voltage = M.data(:, 1); +counts = M.data(:, 2); +plot(counts, voltage, 'b*-', 'LineWidth', 2, 'MarkerSize', 15); +coeffs = polyfit(counts, voltage, 1); +fittedC = linspace(min(counts), max(counts), 500); +fittedV = polyval(coeffs, fittedC); +hold on +plot(fittedC, fittedV, 'r-', 'LineWidth', 3); + +slope = coeffs(1) +y_intersection = coeffs(2) \ No newline at end of file diff --git a/Tools/tests-host/data/px4io_v1.3.csv b/Tools/tests-host/data/px4io_v1.3.csv new file mode 100644 index 000000000..2100d840a --- /dev/null +++ b/Tools/tests-host/data/px4io_v1.3.csv @@ -0,0 +1,70 @@ +voltage, counts +4.3, 950 +4.4, 964 +4.5, 986 +4.6, 1009 +4.7, 1032 +4.8, 1055 +4.9, 1078 +5.0, 1101 +5.2, 1124 +5.3, 1148 +5.4, 1171 +5.5, 1195 +6.0, 1304 +6.1, 1329 +6.2, 1352 +7.0, 1517 +7.1, 1540 +7.2, 1564 +7.3, 1585 +7.4, 1610 +7.5, 1636 +8.0, 1728 +8.1, 1752 +8.2, 1755 +8.3, 1798 +8.4, 1821 +9.0, 1963 +9.1, 1987 +9.3, 2010 +9.4, 2033 +10.0, 2174 +10.1, 2198 +10.2, 2221 +10.3, 2245 +10.4, 2268 +11.0, 2385 +11.1, 2409 +11.2, 2432 +11.3, 2456 +11.4, 2480 +11.5, 2502 +11.6, 2526 +11.7, 2550 +11.8, 2573 +11.9, 2597 +12.0, 2621 +12.1, 2644 +12.3, 2668 +12.4, 2692 +12.5, 2716 +12.6, 2737 +12.7, 2761 +13.0, 2832 +13.5, 2950 +13.6, 2973 +14.1, 3068 +14.2, 3091 +14.7, 3209 +15.0, 3280 +15.1, 3304 +15.5, 3374 +15.6, 3397 +15.7, 3420 +16.0, 3492 +16.1, 3514 +16.2, 3538 +16.9, 3680 +17.0, 3704 +17.1, 3728 \ No newline at end of file -- cgit v1.2.3 From 956c084f31af9ec2aa80d61eee17e7506b4c7172 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 21 Jul 2014 13:31:35 +0200 Subject: Fit IO voltage estimation using a new dataset, cross-validated with a second unit. Pending testing --- src/modules/px4iofirmware/registers.c | 23 +++++------------------ 1 file changed, 5 insertions(+), 18 deletions(-) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index fcd53f1f1..7fbb0ecf1 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -739,30 +739,17 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val { /* * Coefficients here derived by measurement of the 5-16V - * range on one unit: + * range on one unit, validated on sample points of another unit * - * V counts - * 5 1001 - * 6 1219 - * 7 1436 - * 8 1653 - * 9 1870 - * 10 2086 - * 11 2303 - * 12 2522 - * 13 2738 - * 14 2956 - * 15 3172 - * 16 3389 + * Data in Tools/tests-host/data folder. * - * slope = 0.0046067 - * intercept = 0.3863 + * slope = 0.004585267878277 (int: 4585) + * intercept = 0.016646394188076 (int: 16646 * - * Intercept corrected for best results @ 12V. */ unsigned counts = adc_measure(ADC_VBATT); if (counts != 0xffff) { - unsigned mV = (4150 + (counts * 46)) / 10 - 200; + unsigned mV = (16646 + (counts * 4585)) / 1000; unsigned corrected = (mV * r_page_setup[PX4IO_P_SETUP_VBATT_SCALE]) / 10000; r_page_status[PX4IO_P_STATUS_VBATT] = corrected; -- cgit v1.2.3 From 0fc73a1484ac9e9cbc2f52ec7e81b28a109777eb Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 21 Jul 2014 13:46:38 +0200 Subject: Fix comment, missing brace in comment --- src/modules/px4iofirmware/registers.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 7fbb0ecf1..59b3043aa 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -744,7 +744,7 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val * Data in Tools/tests-host/data folder. * * slope = 0.004585267878277 (int: 4585) - * intercept = 0.016646394188076 (int: 16646 + * intercept = 0.016646394188076 (int: 16646) * */ unsigned counts = adc_measure(ADC_VBATT); -- cgit v1.2.3 From 331623bbd40978adf14c2034e75f31c937c34fba Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 21 Jul 2014 13:48:59 +0200 Subject: Fix missing line endings --- Tools/tests-host/data/fit_linear_voltage.m | 2 +- Tools/tests-host/data/px4io_v1.3.csv | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/tests-host/data/fit_linear_voltage.m b/Tools/tests-host/data/fit_linear_voltage.m index a0384b486..7d0c2c27f 100644 --- a/Tools/tests-host/data/fit_linear_voltage.m +++ b/Tools/tests-host/data/fit_linear_voltage.m @@ -11,4 +11,4 @@ hold on plot(fittedC, fittedV, 'r-', 'LineWidth', 3); slope = coeffs(1) -y_intersection = coeffs(2) \ No newline at end of file +y_intersection = coeffs(2) diff --git a/Tools/tests-host/data/px4io_v1.3.csv b/Tools/tests-host/data/px4io_v1.3.csv index 2100d840a..b41ee8f1f 100644 --- a/Tools/tests-host/data/px4io_v1.3.csv +++ b/Tools/tests-host/data/px4io_v1.3.csv @@ -67,4 +67,4 @@ voltage, counts 16.2, 3538 16.9, 3680 17.0, 3704 -17.1, 3728 \ No newline at end of file +17.1, 3728 -- cgit v1.2.3 From 178b0f7399ab881e44f2d2ecff809aea53a4397d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 21 Jul 2014 19:25:23 +0200 Subject: Cross-check with nominal values from divider --- src/modules/px4iofirmware/registers.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 59b3043aa..8c15c66c1 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -743,13 +743,15 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val * * Data in Tools/tests-host/data folder. * - * slope = 0.004585267878277 (int: 4585) + * measured slope = 0.004585267878277 (int: 4585) + * nominal theoretic slope: 0.00459340659 (int: 4593) * intercept = 0.016646394188076 (int: 16646) + * nominal theoretic intercept: 0.00 (int: 0) * */ unsigned counts = adc_measure(ADC_VBATT); if (counts != 0xffff) { - unsigned mV = (16646 + (counts * 4585)) / 1000; + unsigned mV = (0 + (counts * 4593)) / 1000; unsigned corrected = (mV * r_page_setup[PX4IO_P_SETUP_VBATT_SCALE]) / 10000; r_page_status[PX4IO_P_STATUS_VBATT] = corrected; -- cgit v1.2.3 From 07d11583bb0926ac9fe1cf2f1c7e11c683606a4b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 21 Jul 2014 20:21:20 +0200 Subject: Rely on theoretical value, as the closed-loop test with multimeter suggests this is the most accurate measurement --- src/modules/px4iofirmware/registers.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/px4iofirmware/registers.c b/src/modules/px4iofirmware/registers.c index 8c15c66c1..43161aa70 100644 --- a/src/modules/px4iofirmware/registers.c +++ b/src/modules/px4iofirmware/registers.c @@ -751,7 +751,7 @@ registers_get(uint8_t page, uint8_t offset, uint16_t **values, unsigned *num_val */ unsigned counts = adc_measure(ADC_VBATT); if (counts != 0xffff) { - unsigned mV = (0 + (counts * 4593)) / 1000; + unsigned mV = (166460 + (counts * 45934)) / 10000; unsigned corrected = (mV * r_page_setup[PX4IO_P_SETUP_VBATT_SCALE]) / 10000; r_page_status[PX4IO_P_STATUS_VBATT] = corrected; -- cgit v1.2.3 From 940becd0c1e39168e4836db5927e989f2d780ad3 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Tue, 22 Jul 2014 02:55:14 +0400 Subject: UAVCAN update: Mako dependency removed --- uavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uavcan b/uavcan index 767462c99..dca2611c3 160000 --- a/uavcan +++ b/uavcan @@ -1 +1 @@ -Subproject commit 767462c9924d7afbb789dc3e4c76d31261c557d3 +Subproject commit dca2611c3186eaa1cac42557f07b013e2dc633d3 -- cgit v1.2.3 From 1b5d4e5bd4fbee8f994c95d69be7660fd211d2f4 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 22 Jul 2014 17:42:34 +0200 Subject: Comment out uavcan due to build breakage, will go back in ASAP --- makefiles/config_px4fmu-v2_default.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index a498a1b40..fea1bade3 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -74,7 +74,7 @@ MODULES += modules/commander MODULES += modules/navigator MODULES += modules/mavlink MODULES += modules/gpio_led -MODULES += modules/uavcan +#MODULES += modules/uavcan # # Estimation modules (EKF/ SO3 / other filters) -- cgit v1.2.3 From e6594e519295ec081c6f962fca6b4fbdd190846f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 22 Jul 2014 10:20:10 +0900 Subject: tone_alarm: add EKF_WARNING tune Conflicts: mavlink/include/mavlink/v1.0 --- src/drivers/drv_tone_alarm.h | 1 + src/drivers/stm32/tone_alarm/tone_alarm.cpp | 2 ++ 2 files changed, 3 insertions(+) diff --git a/src/drivers/drv_tone_alarm.h b/src/drivers/drv_tone_alarm.h index b7981e9c4..19f792d19 100644 --- a/src/drivers/drv_tone_alarm.h +++ b/src/drivers/drv_tone_alarm.h @@ -149,6 +149,7 @@ enum { TONE_GPS_WARNING_TUNE, TONE_ARMING_FAILURE_TUNE, TONE_PARACHUTE_RELEASE_TUNE, + TONE_EKF_WARNING_TUNE, TONE_NUMBER_OF_TUNES }; diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp index 810f4aacc..03c7bd399 100644 --- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp +++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp @@ -336,6 +336,7 @@ ToneAlarm::ToneAlarm() : _default_tunes[TONE_GPS_WARNING_TUNE] = "MFT255L4AAAL1F#"; //gps warning slow _default_tunes[TONE_ARMING_FAILURE_TUNE] = "MFT255L4<< Date: Sat, 19 Jul 2014 14:38:39 +0200 Subject: code style only: Fix indendation in mavlink.h --- src/modules/mavlink/mavlink_main.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index da989d6c5..adca0e88f 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -250,13 +250,13 @@ private: MavlinkOrbSubscription *_subscriptions; MavlinkStream *_streams; - MavlinkMissionManager *_mission_manager; + MavlinkMissionManager *_mission_manager; - orb_advert_t _mission_pub; + orb_advert_t _mission_pub; int _mission_result_sub; - MAVLINK_MODE _mode; + MAVLINK_MODE _mode; - mavlink_channel_t _channel; + mavlink_channel_t _channel; struct mavlink_logbuffer _logbuffer; unsigned int _total_counter; -- cgit v1.2.3 From 0c0b1a4c666671e964d295fe6aea64d7b6a98fc9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 14:59:13 +0200 Subject: Print mavlink radio module rates --- src/modules/mavlink/mavlink_main.cpp | 51 ++++++++++++++++++++++++++++++-- src/modules/mavlink/mavlink_main.h | 10 +++++++ src/modules/mavlink/mavlink_receiver.cpp | 3 +- 3 files changed, 59 insertions(+), 5 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 76b5459a3..e25851c7d 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -247,6 +247,7 @@ Mavlink::Mavlink() : _subscribe_to_stream(nullptr), _subscribe_to_stream_rate(0.0f), _flow_control_enabled(true), + _rstatus{}, _message_buffer{}, _message_buffer_mutex{}, _param_initialized(false), @@ -424,6 +425,29 @@ Mavlink::destroy_all_instances() return OK; } +int +Mavlink::get_status_all_instances() +{ + Mavlink *inst = ::_mavlink_instances; + + unsigned iterations = 0; + + warnx("waiting for instances to stop"); + + while (inst != nullptr) { + + printf("instance #%u:\n", iterations); + inst->display_status(); + + /* move on */ + inst = inst->next; + iterations++; + } + + /* return an error if there are no instances */ + return (iterations == 0); +} + bool Mavlink::instance_exists(const char *device_name, Mavlink *self) { @@ -1395,7 +1419,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("GPS_GLOBAL_ORIGIN", 0.5f); configure_stream("HIGHRES_IMU", 1.0f * rate_mult); configure_stream("ATTITUDE", 10.0f * rate_mult); - configure_stream("VFR_HUD", 10.0f * rate_mult); + configure_stream("VFR_HUD", 8.0f * rate_mult); configure_stream("GPS_RAW_INT", 1.0f * rate_mult); configure_stream("GLOBAL_POSITION_INT", 3.0f * rate_mult); configure_stream("LOCAL_POSITION_NED", 3.0f * rate_mult); @@ -1665,6 +1689,27 @@ void Mavlink::display_status() { warnx("running"); + + if (_rstatus.timestamp > 0) { + printf("\ttime:\t%llu\tus\n", _rstatus.heartbeat_time); + + switch (_rstatus.type) { + case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: + printf("\t3DR RADIO\n"); + break; + default: + printf("\tUNKNOWN RADIO\n"); + break; + } + + printf("\trssi:\t%d\t\n", _rstatus.rssi); + printf("\tremote rssi:\t%u\tus\n", _rstatus.remote_rssi); + printf("\ttxbuf:\t%u\tus\n", _rstatus.txbuf); + printf("\tnoise:\t%d\tus\n", _rstatus.noise); + printf("\tremote noise:\t%u\tus\n", _rstatus.remote_noise); + printf("\trx errors:\t%u\tus\n", _rstatus.rxerrors); + printf("\tfixed:\t%u\tus\n", _rstatus.fixed); + } } int @@ -1752,8 +1797,8 @@ int mavlink_main(int argc, char *argv[]) } else if (!strcmp(argv[1], "stop-all")) { return Mavlink::destroy_all_instances(); - // } else if (!strcmp(argv[1], "status")) { - // mavlink::g_mavlink->status(); + } else if (!strcmp(argv[1], "status")) { + return Mavlink::get_status_all_instances(); } else if (!strcmp(argv[1], "stream")) { return Mavlink::stream_command(argc, argv); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index adca0e88f..d51120462 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -51,6 +51,7 @@ #include #include #include +#include #include "mavlink_bridge_header.h" #include "mavlink_orb_subscription.h" @@ -97,6 +98,8 @@ public: static int destroy_all_instances(); + static int get_status_all_instances(); + static bool instance_exists(const char *device_name, Mavlink *self); static void forward_message(const mavlink_message_t *msg, Mavlink *self); @@ -229,6 +232,11 @@ public: */ void count_txerr(); + /** + * Get the receive status of this MAVLink link + */ + struct telemetry_status_s& get_rx_status() { return _rstatus; } + protected: Mavlink *next; @@ -285,6 +293,8 @@ private: bool _flow_control_enabled; + struct telemetry_status_s _rstatus; ///< receive status + struct mavlink_message_buffer { int write_ptr; int read_ptr; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 3ee7ec34d..528c8b72a 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -400,8 +400,7 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) mavlink_radio_status_t rstatus; mavlink_msg_radio_status_decode(msg, &rstatus); - struct telemetry_status_s tstatus; - memset(&tstatus, 0, sizeof(tstatus)); + struct telemetry_status_s &tstatus = _mavlink->get_rx_status(); tstatus.timestamp = hrt_absolute_time(); tstatus.heartbeat_time = _telemetry_heartbeat_time; -- cgit v1.2.3 From 91becef344833dbb19230ec3f3c69750bce216e1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 15:56:37 +0200 Subject: Cleanup of heartbeat handling and status printing. Ready to go mainline --- src/modules/mavlink/mavlink_main.cpp | 32 +++++++++++++++++------------- src/modules/mavlink/mavlink_receiver.cpp | 20 +++++++++++-------- src/modules/mavlink/mavlink_receiver.h | 1 - src/modules/uORB/topics/telemetry_status.h | 3 ++- 4 files changed, 32 insertions(+), 24 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index e25851c7d..0e8f17c77 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -432,11 +432,9 @@ Mavlink::get_status_all_instances() unsigned iterations = 0; - warnx("waiting for instances to stop"); - while (inst != nullptr) { - printf("instance #%u:\n", iterations); + printf("\ninstance #%u:\n", iterations); inst->display_status(); /* move on */ @@ -1688,27 +1686,33 @@ Mavlink::start(int argc, char *argv[]) void Mavlink::display_status() { - warnx("running"); + + if (_rstatus.heartbeat_time > 0) { + printf("\theartbeat:\t%llu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time)); + } if (_rstatus.timestamp > 0) { - printf("\ttime:\t%llu\tus\n", _rstatus.heartbeat_time); + + printf("\ttype:\t\t"); switch (_rstatus.type) { case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: - printf("\t3DR RADIO\n"); + printf("3DR RADIO\n"); break; default: - printf("\tUNKNOWN RADIO\n"); + printf("UNKNOWN RADIO\n"); break; } - printf("\trssi:\t%d\t\n", _rstatus.rssi); - printf("\tremote rssi:\t%u\tus\n", _rstatus.remote_rssi); - printf("\ttxbuf:\t%u\tus\n", _rstatus.txbuf); - printf("\tnoise:\t%d\tus\n", _rstatus.noise); - printf("\tremote noise:\t%u\tus\n", _rstatus.remote_noise); - printf("\trx errors:\t%u\tus\n", _rstatus.rxerrors); - printf("\tfixed:\t%u\tus\n", _rstatus.fixed); + printf("\trssi:\t\t%d\n", _rstatus.rssi); + printf("\tremote rssi:\t%u\n", _rstatus.remote_rssi); + printf("\ttxbuf:\t\t%u\n", _rstatus.txbuf); + printf("\tnoise:\t\t%d\n", _rstatus.noise); + printf("\tremote noise:\t%u\n", _rstatus.remote_noise); + printf("\trx errors:\t%u\n", _rstatus.rxerrors); + printf("\tfixed:\t\t%u\n", _rstatus.fixed); + } else { + printf("\tno telem status.\n"); } } diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 528c8b72a..454d730d8 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -111,7 +111,6 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) : _telemetry_status_pub(-1), _rc_pub(-1), _manual_pub(-1), - _telemetry_heartbeat_time(0), _radio_status_available(false), _control_mode_sub(orb_subscribe(ORB_ID(vehicle_control_mode))), _hil_frames(0), @@ -403,7 +402,8 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) struct telemetry_status_s &tstatus = _mavlink->get_rx_status(); tstatus.timestamp = hrt_absolute_time(); - tstatus.heartbeat_time = _telemetry_heartbeat_time; + tstatus.telem_time = tstatus.timestamp; + /* tstatus.heartbeat_time is set by system heartbeats */ tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO; tstatus.rssi = rstatus.rssi; tstatus.remote_rssi = rstatus.remrssi; @@ -460,16 +460,20 @@ MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) /* ignore own heartbeats, accept only heartbeats from GCS */ if (msg->sysid != mavlink_system.sysid && hb.type == MAV_TYPE_GCS) { - _telemetry_heartbeat_time = hrt_absolute_time(); + + struct telemetry_status_s &tstatus = _mavlink->get_rx_status(); + + hrt_abstime tnow = hrt_absolute_time(); + + /* always set heartbeat, publish only if telemetry link not up */ + tstatus.heartbeat_time = tnow; /* if no radio status messages arrive, lets at least publish that heartbeats were received */ if (!_radio_status_available) { - struct telemetry_status_s tstatus; - memset(&tstatus, 0, sizeof(tstatus)); - - tstatus.timestamp = _telemetry_heartbeat_time; - tstatus.heartbeat_time = _telemetry_heartbeat_time; + tstatus.timestamp = tnow; + /* telem_time indicates the timestamp of a telemetry status packet and we got none */ + tstatus.telem_time = 0; tstatus.type = TELEMETRY_STATUS_RADIO_TYPE_GENERIC; if (_telemetry_status_pub < 0) { diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index b64a060e3..f4d0c52d8 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -148,7 +148,6 @@ private: orb_advert_t _telemetry_status_pub; orb_advert_t _rc_pub; orb_advert_t _manual_pub; - hrt_abstime _telemetry_heartbeat_time; bool _radio_status_available; int _control_mode_sub; int _hil_frames; diff --git a/src/modules/uORB/topics/telemetry_status.h b/src/modules/uORB/topics/telemetry_status.h index 3347724a5..1297c1a9d 100644 --- a/src/modules/uORB/topics/telemetry_status.h +++ b/src/modules/uORB/topics/telemetry_status.h @@ -57,7 +57,8 @@ enum TELEMETRY_STATUS_RADIO_TYPE { struct telemetry_status_s { uint64_t timestamp; - uint64_t heartbeat_time; /**< Time of last received heartbeat from remote system */ + uint64_t heartbeat_time; /**< Time of last received heartbeat from remote system */ + uint64_t telem_time; /**< Time of last received telemetry status packet, 0 for none */ enum TELEMETRY_STATUS_RADIO_TYPE type; /**< type of the radio hardware */ uint8_t rssi; /**< local signal strength */ uint8_t remote_rssi; /**< remote signal strength */ -- cgit v1.2.3 From 63f1ee184a63ecabd93ce0cfa91afe97fe7e65d8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 15:57:42 +0200 Subject: Add hint that heartbeats are only considered if coming from a GCS --- src/modules/mavlink/mavlink_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 0e8f17c77..7bd2b9754 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1688,7 +1688,7 @@ Mavlink::display_status() { if (_rstatus.heartbeat_time > 0) { - printf("\theartbeat:\t%llu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time)); + printf("\tGCS heartbeat:\t%llu us ago\n", hrt_elapsed_time(&_rstatus.heartbeat_time)); } if (_rstatus.timestamp > 0) { -- cgit v1.2.3 From b344b94d3039273a1659a4b5640e7dc197922767 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 19 Jul 2014 16:00:37 +0200 Subject: Fix code style, no actual code edits --- src/modules/mavlink/mavlink_main.cpp | 170 +++++++++++++++++++---------------- 1 file changed, 94 insertions(+), 76 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 7bd2b9754..cb8c298c0 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -81,7 +81,7 @@ #include "mavlink_commands.h" #ifndef MAVLINK_CRC_EXTRA - #error MAVLINK_CRC_EXTRA has to be defined on PX4 systems +#error MAVLINK_CRC_EXTRA has to be defined on PX4 systems #endif /* oddly, ERROR is not defined for c++ */ @@ -154,7 +154,8 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length instance = Mavlink::get_instance(6); break; #endif - default: + + default: return; } @@ -169,17 +170,16 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length int buf_free = 0; if (instance->get_flow_control_enabled() - && ioctl(uart, FIONWRITE, (unsigned long)&buf_free) == 0) { + && ioctl(uart, FIONWRITE, (unsigned long)&buf_free) == 0) { /* Disable hardware flow control: * if no successful write since a defined time * and if the last try was not the last successful write */ if (last_write_try_times[(unsigned)channel] != 0 && - hrt_elapsed_time(&last_write_success_times[(unsigned)channel]) > 500 * 1000UL && - last_write_success_times[(unsigned)channel] != - last_write_try_times[(unsigned)channel]) - { + hrt_elapsed_time(&last_write_success_times[(unsigned)channel]) > 500 * 1000UL && + last_write_success_times[(unsigned)channel] != + last_write_try_times[(unsigned)channel]) { warnx("DISABLING HARDWARE FLOW CONTROL"); instance->enable_flow_control(false); } @@ -202,8 +202,10 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length } ssize_t ret = write(uart, ch, desired); + if (ret != desired) { instance->count_txerr(); + } else { last_write_success_times[(unsigned)channel] = last_write_try_times[(unsigned)channel]; } @@ -232,33 +234,33 @@ Mavlink::Mavlink() : _mission_result_sub(-1), _mode(MAVLINK_MODE_NORMAL), _channel(MAVLINK_COMM_0), - _logbuffer{}, - _total_counter(0), - _receive_thread{}, - _verbose(false), - _forwarding_on(false), - _passing_on(false), - _ftp_on(false), - _uart_fd(-1), - _baudrate(57600), - _datarate(10000), - _mavlink_param_queue_index(0), - mavlink_link_termination_allowed(false), - _subscribe_to_stream(nullptr), - _subscribe_to_stream_rate(0.0f), - _flow_control_enabled(true), - _rstatus{}, - _message_buffer{}, - _message_buffer_mutex{}, - _param_initialized(false), - _param_system_id(0), - _param_component_id(0), - _param_system_type(0), - _param_use_hil_gps(0), - -/* performance counters */ - _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")), - _txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe")) + _logbuffer {}, + _total_counter(0), + _receive_thread {}, + _verbose(false), + _forwarding_on(false), + _passing_on(false), + _ftp_on(false), + _uart_fd(-1), + _baudrate(57600), + _datarate(10000), + _mavlink_param_queue_index(0), + mavlink_link_termination_allowed(false), + _subscribe_to_stream(nullptr), + _subscribe_to_stream_rate(0.0f), + _flow_control_enabled(true), + _rstatus {}, + _message_buffer {}, + _message_buffer_mutex {}, + _param_initialized(false), + _param_system_id(0), + _param_component_id(0), + _param_system_type(0), + _param_use_hil_gps(0), + + /* performance counters */ + _loop_perf(perf_alloc(PC_ELAPSED, "mavlink_el")), + _txerr_perf(perf_alloc(PC_COUNT, "mavlink_txe")) { fops.ioctl = (int (*)(file *, int, long unsigned int))&mavlink_dev_ioctl; @@ -637,7 +639,8 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios * case 921600: speed = B921600; break; default: - warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\t9600, 19200, 38400, 57600\t\n115200\n230400\n460800\n921600\n", baud); + warnx("ERROR: Unsupported baudrate: %d\n\tsupported examples:\n\t9600, 19200, 38400, 57600\t\n115200\n230400\n460800\n921600\n", + baud); return -EINVAL; } @@ -867,8 +870,9 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { mavlink_param_request_list_t req; mavlink_msg_param_request_list_decode(msg, &req); + if (req.target_system == mavlink_system.sysid && - (req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) { + (req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) { /* Start sending parameters */ mavlink_pm_start_queued_send(); send_statustext_info("[pm] sending list"); @@ -883,7 +887,9 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav mavlink_param_set_t mavlink_param_set; mavlink_msg_param_set_decode(msg, &mavlink_param_set); - if (mavlink_param_set.target_system == mavlink_system.sysid && ((mavlink_param_set.target_component == mavlink_system.compid) || (mavlink_param_set.target_component == MAV_COMP_ID_ALL))) { + if (mavlink_param_set.target_system == mavlink_system.sysid + && ((mavlink_param_set.target_component == mavlink_system.compid) + || (mavlink_param_set.target_component == MAV_COMP_ID_ALL))) { /* local name buffer to enforce null-terminated string */ char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; strncpy(name, mavlink_param_set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); @@ -910,7 +916,9 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav mavlink_param_request_read_t mavlink_param_request_read; mavlink_msg_param_request_read_decode(msg, &mavlink_param_request_read); - if (mavlink_param_request_read.target_system == mavlink_system.sysid && ((mavlink_param_request_read.target_component == mavlink_system.compid) || (mavlink_param_request_read.target_component == MAV_COMP_ID_ALL))) { + if (mavlink_param_request_read.target_system == mavlink_system.sysid + && ((mavlink_param_request_read.target_component == mavlink_system.compid) + || (mavlink_param_request_read.target_component == MAV_COMP_ID_ALL))) { /* when no index is given, loop through string ids and compare them */ if (mavlink_param_request_read.param_index == -1) { /* local name buffer to enforce null-terminated string */ @@ -973,15 +981,17 @@ Mavlink::send_statustext(unsigned severity, const char *string) /* Map severity */ switch (severity) { - case MAVLINK_IOC_SEND_TEXT_INFO: - statustext.severity = MAV_SEVERITY_INFO; - break; - case MAVLINK_IOC_SEND_TEXT_CRITICAL: - statustext.severity = MAV_SEVERITY_CRITICAL; - break; - case MAVLINK_IOC_SEND_TEXT_EMERGENCY: - statustext.severity = MAV_SEVERITY_EMERGENCY; - break; + case MAVLINK_IOC_SEND_TEXT_INFO: + statustext.severity = MAV_SEVERITY_INFO; + break; + + case MAVLINK_IOC_SEND_TEXT_CRITICAL: + statustext.severity = MAV_SEVERITY_CRITICAL; + break; + + case MAVLINK_IOC_SEND_TEXT_EMERGENCY: + statustext.severity = MAV_SEVERITY_EMERGENCY; + break; } mavlink_msg_statustext_send(_channel, statustext.severity, statustext.text); @@ -1098,12 +1108,14 @@ Mavlink::message_buffer_init(int size) _message_buffer.size = size; _message_buffer.write_ptr = 0; _message_buffer.read_ptr = 0; - _message_buffer.data = (char*)malloc(_message_buffer.size); + _message_buffer.data = (char *)malloc(_message_buffer.size); int ret; + if (_message_buffer.data == 0) { ret = ERROR; _message_buffer.size = 0; + } else { ret = OK; } @@ -1475,7 +1487,8 @@ Mavlink::task_main(int argc, char *argv[]) if (_subscribe_to_stream != nullptr) { if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) { if (_subscribe_to_stream_rate > 0.0f) { - warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, (double)_subscribe_to_stream_rate); + warnx("stream %s on device %s enabled with rate %.1f Hz", _subscribe_to_stream, _device_name, + (double)_subscribe_to_stream_rate); } else { warnx("stream %s on device %s disabled", _subscribe_to_stream, _device_name); @@ -1514,45 +1527,46 @@ Mavlink::task_main(int argc, char *argv[]) bool is_part; uint8_t *read_ptr; - uint8_t *write_ptr; + uint8_t *write_ptr; pthread_mutex_lock(&_message_buffer_mutex); - int available = message_buffer_get_ptr((void**)&read_ptr, &is_part); + int available = message_buffer_get_ptr((void **)&read_ptr, &is_part); pthread_mutex_unlock(&_message_buffer_mutex); if (available > 0) { - // Reconstruct message from buffer + // Reconstruct message from buffer mavlink_message_t msg; - write_ptr = (uint8_t*)&msg; - - // Pull a single message from the buffer - size_t read_count = available; - if (read_count > sizeof(mavlink_message_t)) { - read_count = sizeof(mavlink_message_t); - } - - memcpy(write_ptr, read_ptr, read_count); - - // We hold the mutex until after we complete the second part of the buffer. If we don't - // we may end up breaking the empty slot overflow detection semantics when we mark the - // possibly partial read below. - pthread_mutex_lock(&_message_buffer_mutex); - + write_ptr = (uint8_t *)&msg; + + // Pull a single message from the buffer + size_t read_count = available; + + if (read_count > sizeof(mavlink_message_t)) { + read_count = sizeof(mavlink_message_t); + } + + memcpy(write_ptr, read_ptr, read_count); + + // We hold the mutex until after we complete the second part of the buffer. If we don't + // we may end up breaking the empty slot overflow detection semantics when we mark the + // possibly partial read below. + pthread_mutex_lock(&_message_buffer_mutex); + message_buffer_mark_read(read_count); /* write second part of buffer if there is some */ if (is_part && read_count < sizeof(mavlink_message_t)) { - write_ptr += read_count; - available = message_buffer_get_ptr((void**)&read_ptr, &is_part); - read_count = sizeof(mavlink_message_t) - read_count; - memcpy(write_ptr, read_ptr, read_count); + write_ptr += read_count; + available = message_buffer_get_ptr((void **)&read_ptr, &is_part); + read_count = sizeof(mavlink_message_t) - read_count; + memcpy(write_ptr, read_ptr, read_count); message_buffer_mark_read(available); } - - pthread_mutex_unlock(&_message_buffer_mutex); - _mavlink_resend_uart(_channel, &msg); + pthread_mutex_unlock(&_message_buffer_mutex); + + _mavlink_resend_uart(_channel, &msg); } } @@ -1606,6 +1620,7 @@ Mavlink::task_main(int argc, char *argv[]) message_buffer_destroy(); pthread_mutex_destroy(&_message_buffer_mutex); } + /* destroy log buffer */ mavlink_logbuffer_destroy(&_logbuffer); @@ -1627,6 +1642,7 @@ int Mavlink::start_helper(int argc, char *argv[]) /* out of memory */ res = -ENOMEM; warnx("OUT OF MEM"); + } else { /* this will actually only return once MAVLink exits */ res = instance->task_main(argc, argv); @@ -1696,10 +1712,11 @@ Mavlink::display_status() printf("\ttype:\t\t"); switch (_rstatus.type) { - case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: + case TELEMETRY_STATUS_RADIO_TYPE_3DR_RADIO: printf("3DR RADIO\n"); break; - default: + + default: printf("UNKNOWN RADIO\n"); break; } @@ -1711,6 +1728,7 @@ Mavlink::display_status() printf("\tremote noise:\t%u\n", _rstatus.remote_noise); printf("\trx errors:\t%u\n", _rstatus.rxerrors); printf("\tfixed:\t\t%u\n", _rstatus.fixed); + } else { printf("\tno telem status.\n"); } -- cgit v1.2.3 From ef363edfcd810e3b153609f0a723f53db0cd3885 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 19 Jul 2014 17:37:13 +0200 Subject: mavlink: TX/RX rate counters added --- src/modules/mavlink/mavlink_main.cpp | 28 ++++++++++++++++++++++++++++ src/modules/mavlink/mavlink_main.h | 23 +++++++++++++++++++++++ src/modules/mavlink/mavlink_receiver.cpp | 3 +++ 3 files changed, 54 insertions(+) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index cb8c298c0..0c6f8c42f 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -197,6 +197,7 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length if (buf_free < desired) { /* we don't want to send anything just in half, so return */ instance->count_txerr(); + instance->count_txerrbytes(desired); return; } } @@ -205,9 +206,11 @@ mavlink_send_uart_bytes(mavlink_channel_t channel, const uint8_t *ch, int length if (ret != desired) { instance->count_txerr(); + instance->count_txerrbytes(desired); } else { last_write_success_times[(unsigned)channel] = last_write_try_times[(unsigned)channel]; + instance->count_txbytes(desired); } } } @@ -249,6 +252,13 @@ Mavlink::Mavlink() : _subscribe_to_stream(nullptr), _subscribe_to_stream_rate(0.0f), _flow_control_enabled(true), + _bytes_tx(0), + _bytes_txerr(0), + _bytes_rx(0), + _bytes_timestamp(0), + _rate_tx(0.0f), + _rate_txerr(0.0f), + _rate_rx(0.0f), _rstatus {}, _message_buffer {}, _message_buffer_mutex {}, @@ -1570,6 +1580,20 @@ Mavlink::task_main(int argc, char *argv[]) } } + /* update TX/RX rates*/ + if (t > _bytes_timestamp + 1000000) { + if (_bytes_timestamp != 0) { + float dt = (t - _bytes_timestamp) / 1000.0f; + _rate_tx = _bytes_tx / dt; + _rate_txerr = _bytes_txerr / dt; + _rate_rx = _bytes_rx / dt; + _bytes_tx = 0; + _bytes_txerr = 0; + _bytes_rx = 0; + } + _bytes_timestamp = t; + } + perf_end(_loop_perf); } @@ -1732,6 +1756,10 @@ Mavlink::display_status() } else { printf("\tno telem status.\n"); } + printf("\trates:\n"); + printf("\ttx: %.3f kB/s\n", (double)_rate_tx); + printf("\ttxerr: %.3f kB/s\n", (double)_rate_txerr); + printf("\trx: %.3f kB/s\n", (double)_rate_rx); } int diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index d51120462..70d13acb0 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -232,6 +232,21 @@ public: */ void count_txerr(); + /** + * Count transmitted bytes + */ + void count_txbytes(unsigned n) { _bytes_tx += n; }; + + /** + * Count bytes not transmitted because of errors + */ + void count_txerrbytes(unsigned n) { _bytes_txerr += n; }; + + /** + * Count received bytes + */ + void count_rxbytes(unsigned n) { _bytes_rx += n; }; + /** * Get the receive status of this MAVLink link */ @@ -293,6 +308,14 @@ private: bool _flow_control_enabled; + unsigned _bytes_tx; + unsigned _bytes_txerr; + unsigned _bytes_rx; + uint64_t _bytes_timestamp; + float _rate_tx; + float _rate_txerr; + float _rate_rx; + struct telemetry_status_s _rstatus; ///< receive status struct mavlink_message_buffer { diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 454d730d8..54c412ce7 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -958,6 +958,9 @@ MavlinkReceiver::receive_thread(void *arg) _mavlink->handle_message(&msg); } } + + /* count received bytes */ + _mavlink->count_rxbytes(nread); } } -- cgit v1.2.3 From 7f0e67522878d1e850c22553fc53e93283ed92f8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 23 Jul 2014 08:24:56 +0200 Subject: Pass over drivers to reduce build size --- src/drivers/airspeed/module.mk | 2 ++ src/drivers/bma180/module.mk | 2 ++ src/drivers/ets_airspeed/module.mk | 2 ++ src/drivers/hil/module.mk | 2 ++ src/drivers/led/module.mk | 2 ++ src/drivers/md25/module.mk | 2 ++ src/drivers/meas_airspeed/module.mk | 2 ++ src/drivers/ms5611/module.mk | 2 ++ src/drivers/px4flow/module.mk | 2 ++ src/drivers/roboclaw/module.mk | 2 ++ 10 files changed, 20 insertions(+) diff --git a/src/drivers/airspeed/module.mk b/src/drivers/airspeed/module.mk index 4eef06161..5fbc75309 100644 --- a/src/drivers/airspeed/module.mk +++ b/src/drivers/airspeed/module.mk @@ -36,3 +36,5 @@ # SRCS = airspeed.cpp + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/bma180/module.mk b/src/drivers/bma180/module.mk index 4c60ee082..33433307a 100644 --- a/src/drivers/bma180/module.mk +++ b/src/drivers/bma180/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = bma180 SRCS = bma180.cpp + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/ets_airspeed/module.mk b/src/drivers/ets_airspeed/module.mk index 966a5b819..8aaaf0ebb 100644 --- a/src/drivers/ets_airspeed/module.mk +++ b/src/drivers/ets_airspeed/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = ets_airspeed SRCS = ets_airspeed.cpp MODULE_STACKSIZE = 1200 + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/hil/module.mk b/src/drivers/hil/module.mk index f8895f5d5..f1fc49fb3 100644 --- a/src/drivers/hil/module.mk +++ b/src/drivers/hil/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = hil SRCS = hil.cpp + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/led/module.mk b/src/drivers/led/module.mk index 777f3e442..5b7b4491b 100644 --- a/src/drivers/led/module.mk +++ b/src/drivers/led/module.mk @@ -36,3 +36,5 @@ # SRCS = led.cpp + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/md25/module.mk b/src/drivers/md25/module.mk index 13821a6b5..3f9cf2d89 100644 --- a/src/drivers/md25/module.mk +++ b/src/drivers/md25/module.mk @@ -40,3 +40,5 @@ MODULE_COMMAND = md25 SRCS = md25.cpp \ md25_main.cpp + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/meas_airspeed/module.mk b/src/drivers/meas_airspeed/module.mk index 2a15b669f..6f5909978 100644 --- a/src/drivers/meas_airspeed/module.mk +++ b/src/drivers/meas_airspeed/module.mk @@ -42,3 +42,5 @@ SRCS = meas_airspeed.cpp MODULE_STACKSIZE = 1200 EXTRACXXFLAGS = -Weffc++ + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/ms5611/module.mk b/src/drivers/ms5611/module.mk index 20f8aa173..ee74058fc 100644 --- a/src/drivers/ms5611/module.mk +++ b/src/drivers/ms5611/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = ms5611 SRCS = ms5611.cpp ms5611_spi.cpp ms5611_i2c.cpp + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/px4flow/module.mk b/src/drivers/px4flow/module.mk index d3062e457..460bec7b9 100644 --- a/src/drivers/px4flow/module.mk +++ b/src/drivers/px4flow/module.mk @@ -38,3 +38,5 @@ MODULE_COMMAND = px4flow SRCS = px4flow.cpp + +MAXOPTIMIZATION = -Os diff --git a/src/drivers/roboclaw/module.mk b/src/drivers/roboclaw/module.mk index 1abecf198..c5e55bdc3 100644 --- a/src/drivers/roboclaw/module.mk +++ b/src/drivers/roboclaw/module.mk @@ -39,3 +39,5 @@ MODULE_COMMAND = roboclaw SRCS = roboclaw_main.cpp \ RoboClaw.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From a7d2963e2bca060493f787cf637b0e1b0d9d829e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 23 Jul 2014 08:27:45 +0200 Subject: Enable UAVCAN --- makefiles/config_px4fmu-v2_default.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index fea1bade3..a498a1b40 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -74,7 +74,7 @@ MODULES += modules/commander MODULES += modules/navigator MODULES += modules/mavlink MODULES += modules/gpio_led -#MODULES += modules/uavcan +MODULES += modules/uavcan # # Estimation modules (EKF/ SO3 / other filters) -- cgit v1.2.3 From 4722b609ccfa35c438c1ef74caba2793c9e04225 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 23 Jul 2014 11:03:04 +0200 Subject: mavlink: parameters handling moved to MavlinkParametersManager class --- src/modules/mavlink/mavlink_parameters.cpp | 197 +++++++++++++++++++++++++++++ src/modules/mavlink/mavlink_parameters.h | 114 +++++++++++++++++ 2 files changed, 311 insertions(+) create mode 100644 src/modules/mavlink/mavlink_parameters.cpp create mode 100644 src/modules/mavlink/mavlink_parameters.h diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp new file mode 100644 index 000000000..b1dae918c --- /dev/null +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -0,0 +1,197 @@ +/**************************************************************************** + * + * Copyright (c) 2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mavlink_parameters.cpp + * Mavlink parameters manager implementation. + * + * @author Anton Babushkin + */ + +//#include + +#include "mavlink_parameters.h" + +explicit +MavlinkParametersManager::MavlinkParametersManager(Mavlink *mavlink) : MavlinkStream(mavlink), + _send_all_index(-1) +{ +} + +unsigned +MavlinkParametersManager::get_size() +{ + if (_send_all_index() >= 0) { + return MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + + } else { + return 0; + } +} + +void +MavlinkParametersManager::handle_message(const mavlink_message_t *msg) +{ + switch (msg->msgid) { + case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { + /* request all parameters */ + mavlink_param_request_list_t req_list; + mavlink_msg_param_request_list_decode(msg, &req_list); + + if (req_list.target_system == mavlink_system.sysid && + (req_list.target_component == mavlink_system.compid || req_list.target_component == MAV_COMP_ID_ALL)) { + + _send_all_index = 0; + _mavlink->send_statustext_info("[pm] sending list"); + } + break; + } + + case MAVLINK_MSG_ID_PARAM_SET: { + /* set parameter */ + if (msg->msgid == MAVLINK_MSG_ID_PARAM_SET) { + mavlink_param_set_t set; + mavlink_msg_param_set_decode(msg, &set); + + if (set.target_system == mavlink_system.sysid && + (set.target_component == mavlink_system.compid || set.target_component == MAV_COMP_ID_ALL)) { + + /* local name buffer to enforce null-terminated string */ + char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; + strncpy(name, set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); + /* enforce null termination */ + name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; + /* attempt to find parameter, set and send it */ + param_t param = param_find(name); + + if (param == PARAM_INVALID) { + char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; + sprintf(buf, "[pm] unknown param: %s", name); + _mavlink->send_statustext_info(buf); + + } else { + /* set and send parameter */ + param_set(param, &(set.param_value)); + send_param(param); + } + } + } + break; + } + + case MAVLINK_MSG_ID_PARAM_REQUEST_READ: { + /* request one parameter */ + mavlink_param_request_read_t req_read; + mavlink_msg_param_request_read_decode(msg, &req_read); + + if (req_read.target_system == mavlink_system.sysid && + (req_read.target_component == mavlink_system.compid || req_read.target_component == MAV_COMP_ID_ALL)) { + + /* when no index is given, loop through string ids and compare them */ + if (req_read.param_index < 0) { + /* local name buffer to enforce null-terminated string */ + char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; + strncpy(name, req_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); + /* enforce null termination */ + name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; + /* attempt to find parameter and send it */ + send_param(param_find(name)); + + } else { + /* when index is >= 0, send this parameter again */ + send_param(param_for_index(req_read.param_index)); + } + } + break; + } + + default: + break; + } +} + +void +MavlinkParametersManager::send(const hrt_abstime t) +{ + /* send all parameters if requested */ + if (_send_all_index >= 0) { + send_param(param_for_index(_send_all_index)); + _send_all_index++; + if (_send_all_index >= param_count()) { + _send_all_index = -1; + } + } +} + +void +MavlinkParametersManager::send_param(param_t param) +{ + if (param == PARAM_INVALID) { + return; + } + + mavlink_param_value_t msg; + + /* + * get param value, since MAVLink encodes float and int params in the same + * space during transmission, copy param onto float val_buf + */ + if (param_get(param, &msg.param_value) != OK) { + return; + } + + msg.param_count = param_count(); + msg.param_index = param_get_index(param); + + /* copy parameter name */ + strncpy(msg.param_id, param_name(param), MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); + + /* query parameter type */ + param_type_t type = param_type(param); + + /* + * Map onboard parameter type to MAVLink type, + * endianess matches (both little endian) + */ + if (type == PARAM_TYPE_INT32) { + msg.param_type = MAVLINK_TYPE_INT32_T; + + } else if (type == PARAM_TYPE_FLOAT) { + msg.param_type = MAVLINK_TYPE_FLOAT; + + } else { + msg.param_type = MAVLINK_TYPE_FLOAT; + } + + _mavlink->send_message(MAVLINK_MSG_ID_PARAM_VALUE, &msg); +} diff --git a/src/modules/mavlink/mavlink_parameters.h b/src/modules/mavlink/mavlink_parameters.h new file mode 100644 index 000000000..9b7a04a73 --- /dev/null +++ b/src/modules/mavlink/mavlink_parameters.h @@ -0,0 +1,114 @@ +/**************************************************************************** + * + * Copyright (c) 2012-2014 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * @file mavlink_parameters.h + * Mavlink parameters manager definition. + * + * @author Anton Babushkin + */ + +#pragma once + +#include "mavlink_stream.h" + +class MavlinkParametersManager : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkParametersManager::get_name_static(); + } + + static const char *get_name_static() + { + return "PARAM_VALUE"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_PARAM_VALUE; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkParametersManager(mavlink); + } + + unsigned get_size(); + + void handle_message(const mavlink_message_t *msg); + + /** + * Send one parameter identified by index. + * + * @param index The index of the parameter to send. + * @return zero on success, nonzero else. + */ + void start_send_one(int index); + + + /** + * Send one parameter identified by name. + * + * @param name The index of the parameter to send. + * @return zero on success, nonzero else. + */ + int start_send_for_name(const char *name); + + /** + * Start sending the parameter queue. + * + * This function will not directly send parameters, but instead + * activate the sending of one parameter on each call of + * mavlink_pm_queued_send(). + * @see mavlink_pm_queued_send() + */ + void start_send_all(); + +private: + int _send_all_index; + + /* do not allow top copying this class */ + MavlinkParametersManager(MavlinkParametersManager &); + MavlinkParametersManager& operator = (const MavlinkParametersManager &); + +protected: + explicit MavlinkParametersManager(Mavlink *mavlink); + + void subscribe() {} + + void send(const hrt_abstime t); + + void send_param(param_t param); +}; -- cgit v1.2.3 From 344a34bb725a65769a227157f41363fd5d180a14 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 23 Jul 2014 11:03:37 +0200 Subject: mavlink: MavlinkStream API updated --- src/modules/mavlink/mavlink_stream.cpp | 5 +++-- src/modules/mavlink/mavlink_stream.h | 13 ++++++++++--- 2 files changed, 13 insertions(+), 5 deletions(-) diff --git a/src/modules/mavlink/mavlink_stream.cpp b/src/modules/mavlink/mavlink_stream.cpp index 79dc23cc6..da3a55172 100644 --- a/src/modules/mavlink/mavlink_stream.cpp +++ b/src/modules/mavlink/mavlink_stream.cpp @@ -71,11 +71,12 @@ int MavlinkStream::update(const hrt_abstime t) { uint64_t dt = t - _last_sent; + unsigned int interval = _interval * _mavlink->get_rate_mult(); - if (dt > 0 && dt >= _interval) { + if (dt > 0 && dt >= interval) { /* interval expired, send message */ send(t); - _last_sent = (t / _interval) * _interval; + _last_sent = t; return 0; } diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h index 7d3afbbb5..646931c07 100644 --- a/src/modules/mavlink/mavlink_stream.h +++ b/src/modules/mavlink/mavlink_stream.h @@ -46,8 +46,6 @@ class Mavlink; class MavlinkStream; -#include "mavlink_main.h" - class MavlinkStream { @@ -70,7 +68,6 @@ public: * @return the inveral in microseconds (us) between messages */ unsigned get_interval() { return _interval; } - void set_channel(mavlink_channel_t channel); /** * @return 0 if updated / sent, -1 if unchanged @@ -82,6 +79,16 @@ public: virtual const char *get_name() const = 0; virtual uint8_t get_id() = 0; + /** + * @return true if steam rate shouldn't be adjusted + */ + virtual bool const_rate() { return false; } + + /** + * Get maximal total messages size on update + */ + virtual unsigned get_size() = 0; + protected: Mavlink * _mavlink; unsigned int _interval; -- cgit v1.2.3 From a5f2d1b06645d4db33751aa8392fcbaf7f0856cc Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 23 Jul 2014 11:11:49 +0200 Subject: mavlink: new message sending API, includes fixed --- src/modules/mavlink/mavlink_ftp.h | 1 + src/modules/mavlink/mavlink_main.cpp | 306 +-- src/modules/mavlink/mavlink_main.h | 58 +- src/modules/mavlink/mavlink_messages.cpp | 3186 ++++++++++++++-------------- src/modules/mavlink/mavlink_messages.h | 4 +- src/modules/mavlink/mavlink_mission.cpp | 26 +- src/modules/mavlink/mavlink_parameters.cpp | 6 +- src/modules/mavlink/mavlink_parameters.h | 3 + src/modules/mavlink/module.mk | 1 + 9 files changed, 1715 insertions(+), 1876 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h index 59237a4c4..1bd1158fb 100644 --- a/src/modules/mavlink/mavlink_ftp.h +++ b/src/modules/mavlink/mavlink_ftp.h @@ -55,6 +55,7 @@ #include #include "mavlink_messages.h" +#include "mavlink_main.h" class MavlinkFTP { diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index e3c452fb2..dca76c950 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -102,6 +102,7 @@ static Mavlink *_mavlink_instances = nullptr; static struct file_operations fops; static const uint8_t mavlink_message_lengths[256] = MAVLINK_MESSAGE_LENGTHS; +static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS; /** * mavlink app start / stop handling function @@ -130,6 +131,7 @@ Mavlink::Mavlink() : _subscriptions(nullptr), _streams(nullptr), _mission_manager(nullptr), + _parameters_manager(nullptr), _mission_pub(-1), _mission_result_sub(-1), _mode(MAVLINK_MODE_NORMAL), @@ -145,6 +147,7 @@ Mavlink::Mavlink() : _baudrate(57600), _datarate(1000), _datarate_events(500), + _rate_mult(0.0f), _mavlink_param_queue_index(0), mavlink_link_termination_allowed(false), _subscribe_to_stream(nullptr), @@ -687,18 +690,23 @@ Mavlink::set_hil_enabled(bool hil_enabled) return ret; } -bool -Mavlink::check_can_send(const int prio, const unsigned packet_len) +void +Mavlink::send_message(const uint8_t msgid, const void *msg) { + /* If the wait until transmit flag is on, only transmit after we've received messages. + Otherwise, transmit all the time. */ + if (!should_transmit()) { + return; + } + /* * Check if the OS buffer is full and disable HW * flow control if it continues to be full */ int buf_free = 0; + (void) ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free); - if (get_flow_control_enabled() - && ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free) == 0) { - + if (get_flow_control_enabled() && buf_free == 0) { /* Disable hardware flow control: * if no successful write since a defined time * and if the last try was not the last successful write @@ -711,36 +719,22 @@ Mavlink::check_can_send(const int prio, const unsigned packet_len) } } - /* If the wait until transmit flag is on, only transmit after we've received messages. - Otherwise, transmit all the time. */ - if (should_transmit()) { - _last_write_try_time = hrt_absolute_time(); + uint8_t payload_len = mavlink_message_lengths[msgid]; + unsigned packet_len = payload_len + MAVLINK_NUM_NON_PAYLOAD_BYTES; - /* check if there is space in the buffer, let it overflow else */ - ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free); + _last_write_try_time = hrt_absolute_time(); - if (buf_free >= (prio <= 0 ? packet_len : TX_BUFFER_GAP)) { - warnx("\t\t\tSKIP %i bytes prio %i", packet_len, (int)prio); - /* we don't want to send anything just in half, so return */ - count_txerr(); - count_txerrbytes(packet_len); - return true; - } + /* check if there is space in the buffer, let it overflow else */ + if (buf_free >= TX_BUFFER_GAP) { + warnx("SKIP msgid %i, %i bytes", msgid, packet_len); + /* no enough space in buffer to send */ + count_txerr(); + count_txerrbytes(packet_len); + return; } - return false; -} -void -Mavlink::send_message(const uint8_t msgid, const void *msg, const int prio) -{ uint8_t buf[MAVLINK_MAX_PACKET_LEN]; - uint8_t payload_len = mavlink_message_lengths[msgid]; - unsigned packet_len = payload_len + MAVLINK_NUM_NON_PAYLOAD_BYTES; - if (!check_can_send(prio, packet_len)) { - return; - } - /* header */ buf[0] = MAVLINK_STX; buf[1] = payload_len; @@ -755,9 +749,9 @@ Mavlink::send_message(const uint8_t msgid, const void *msg, const int prio) /* checksum */ uint16_t checksum; crc_init(&checksum); - crc_accumulate_buffer(&checksum, &buf[1], MAVLINK_CORE_HEADER_LEN + payload_len); + crc_accumulate_buffer(&checksum, (const char*) &buf[1], MAVLINK_CORE_HEADER_LEN + payload_len); #if MAVLINK_CRC_EXTRA - crc_accumulate(crc_extra, &checksum); + crc_accumulate(mavlink_message_crcs[msgid], &checksum); #endif buf[MAVLINK_NUM_HEADER_BYTES + payload_len] = (uint8_t)(checksum & 0xFF); @@ -766,7 +760,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg, const int prio) /* send message to UART */ ssize_t ret = write(_uart_fd, buf, packet_len); - if (ret != packet_len) { + if (ret != (int) packet_len) { count_txerr(); count_txerrbytes(packet_len); @@ -783,7 +777,7 @@ Mavlink::handle_message(const mavlink_message_t *msg) _mission_manager->handle_message(msg); /* handle packet with parameter component */ - mavlink_pm_message_handler(_channel, msg); + _parameters_manager->handle_message(msg); if (get_forwarding_on()) { /* forward any messages to other mavlink instances */ @@ -791,163 +785,6 @@ Mavlink::handle_message(const mavlink_message_t *msg) } } -int -Mavlink::mavlink_pm_queued_send() -{ - if (_mavlink_param_queue_index < param_count()) { - mavlink_pm_send_param(param_for_index(_mavlink_param_queue_index)); - _mavlink_param_queue_index++; - return 0; - - } else { - return 1; - } -} - -void Mavlink::mavlink_pm_start_queued_send() -{ - _mavlink_param_queue_index = 0; -} - -int Mavlink::mavlink_pm_send_param_for_index(uint16_t index) -{ - return mavlink_pm_send_param(param_for_index(index)); -} - -int Mavlink::mavlink_pm_send_param_for_name(const char *name) -{ - return mavlink_pm_send_param(param_find(name)); -} - -int Mavlink::mavlink_pm_send_param(param_t param) -{ - if (param == PARAM_INVALID) { return 1; } - - /* buffers for param transmission */ - char name_buf[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN]; - float val_buf; - mavlink_message_t tx_msg; - - /* query parameter type */ - param_type_t type = param_type(param); - /* copy parameter name */ - strncpy((char *)name_buf, param_name(param), MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); - - /* - * Map onboard parameter type to MAVLink type, - * endianess matches (both little endian) - */ - uint8_t mavlink_type; - - if (type == PARAM_TYPE_INT32) { - mavlink_type = MAVLINK_TYPE_INT32_T; - - } else if (type == PARAM_TYPE_FLOAT) { - mavlink_type = MAVLINK_TYPE_FLOAT; - - } else { - mavlink_type = MAVLINK_TYPE_FLOAT; - } - - /* - * get param value, since MAVLink encodes float and int params in the same - * space during transmission, copy param onto float val_buf - */ - - int ret; - - if ((ret = param_get(param, &val_buf)) != OK) { - return ret; - } - - mavlink_msg_param_value_pack_chan(mavlink_system.sysid, - mavlink_system.compid, - _channel, - &tx_msg, - name_buf, - val_buf, - mavlink_type, - param_count(), - param_get_index(param)); - send_message(&tx_msg); - return OK; -} - -void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mavlink_message_t *msg) -{ - switch (msg->msgid) { - case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { - mavlink_param_request_list_t req; - mavlink_msg_param_request_list_decode(msg, &req); - - if (req.target_system == mavlink_system.sysid && - (req.target_component == mavlink_system.compid || req.target_component == MAV_COMP_ID_ALL)) { - /* Start sending parameters */ - mavlink_pm_start_queued_send(); - send_statustext_info("[pm] sending list"); - } - } break; - - case MAVLINK_MSG_ID_PARAM_SET: { - - /* Handle parameter setting */ - - if (msg->msgid == MAVLINK_MSG_ID_PARAM_SET) { - mavlink_param_set_t mavlink_param_set; - mavlink_msg_param_set_decode(msg, &mavlink_param_set); - - if (mavlink_param_set.target_system == mavlink_system.sysid - && ((mavlink_param_set.target_component == mavlink_system.compid) - || (mavlink_param_set.target_component == MAV_COMP_ID_ALL))) { - /* local name buffer to enforce null-terminated string */ - char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; - strncpy(name, mavlink_param_set.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); - /* enforce null termination */ - name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; - /* attempt to find parameter, set and send it */ - param_t param = param_find(name); - - if (param == PARAM_INVALID) { - char buf[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN]; - sprintf(buf, "[pm] unknown: %s", name); - send_statustext_info(buf); - - } else { - /* set and send parameter */ - param_set(param, &(mavlink_param_set.param_value)); - mavlink_pm_send_param(param); - } - } - } - } break; - - case MAVLINK_MSG_ID_PARAM_REQUEST_READ: { - mavlink_param_request_read_t mavlink_param_request_read; - mavlink_msg_param_request_read_decode(msg, &mavlink_param_request_read); - - if (mavlink_param_request_read.target_system == mavlink_system.sysid - && ((mavlink_param_request_read.target_component == mavlink_system.compid) - || (mavlink_param_request_read.target_component == MAV_COMP_ID_ALL))) { - /* when no index is given, loop through string ids and compare them */ - if (mavlink_param_request_read.param_index == -1) { - /* local name buffer to enforce null-terminated string */ - char name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN + 1]; - strncpy(name, mavlink_param_request_read.param_id, MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN); - /* enforce null termination */ - name[MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN] = '\0'; - /* attempt to find parameter and send it */ - mavlink_pm_send_param_for_name(name); - - } else { - /* when index is >= 0, send this parameter again */ - mavlink_pm_send_param_for_index(mavlink_param_request_read.param_index); - } - } - - } break; - } -} - int Mavlink::send_statustext_info(const char *string) { @@ -1031,11 +868,17 @@ MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic) return sub_new; } +unsigned int +Mavlink::interval_from_rate(float rate) +{ + return (rate > 0.0f) ? (1000000.0f / rate) : 0; +} + int Mavlink::configure_stream(const char *stream_name, const float rate) { /* calculate interval in us, 0 means disabled stream */ - unsigned int interval = (rate > 0.0f) ? (1000000.0f / rate) : 0; + unsigned int interval = interval_from_rate(rate); /* search if stream exists */ MavlinkStream *stream; @@ -1066,10 +909,9 @@ Mavlink::configure_stream(const char *stream_name, const float rate) if (strcmp(stream_name, streams_list[i]->get_name()) == 0) { /* create new instance */ - stream = streams_list[i]->new_instance(); - stream->set_channel(get_channel()); + stream = streams_list[i]->new_instance(this); stream->set_interval(interval); - stream->subscribe(this); + stream->subscribe(); LL_APPEND(_streams, stream); return OK; @@ -1267,7 +1109,26 @@ Mavlink::pass_message(const mavlink_message_t *msg) float Mavlink::get_rate_mult() { - return _datarate / 1000.0f; + return _rate_mult; +} + +void +Mavlink::update_rate_mult() +{ + float const_rate = 0.0f; + float rate = 0.0f; + + MavlinkStream *stream; + LL_FOREACH(_streams, stream) { + if (stream->const_rate()) { + const_rate += stream->get_size() * 1000000.0f / stream->get_interval(); + + } else { + rate += stream->get_size() * 1000000.0f / stream->get_interval(); + } + } + + _rate_mult = ((float)_datarate - const_rate) / (rate - const_rate); } int @@ -1390,6 +1251,8 @@ Mavlink::task_main(int argc, char *argv[]) break; } + update_rate_mult(); + warnx("data rate: %d Bytes/s, port: %s, baud: %d", _datarate, _device_name, _baudrate); /* flush stdout in case MAVLink is about to take it over */ @@ -1452,32 +1315,37 @@ Mavlink::task_main(int argc, char *argv[]) MavlinkCommandsStream commands_stream(this, _channel); - /* add default streams depending on mode and intervals depending on datarate */ - float rate_mult = get_rate_mult(); + /* add default streams depending on mode */ + /* HEARTBEAT is constant rate stream, rate never adjusted */ configure_stream("HEARTBEAT", 1.0f); + /* PARAM_VALUE stream */ + _parameters_manager = (MavlinkParametersManager *) MavlinkParametersManager::new_instance(this); + _parameters_manager->set_interval(interval_from_rate(30.0f)); + LL_APPEND(_streams, _parameters_manager); + switch (_mode) { case MAVLINK_MODE_NORMAL: configure_stream("SYS_STATUS", 1.0f); configure_stream("GPS_GLOBAL_ORIGIN", 0.5f); - configure_stream("HIGHRES_IMU", 1.0f * rate_mult); - configure_stream("ATTITUDE", 10.0f * rate_mult); - configure_stream("VFR_HUD", 8.0f * rate_mult); - configure_stream("GPS_RAW_INT", 1.0f * rate_mult); - configure_stream("GLOBAL_POSITION_INT", 3.0f * rate_mult); - configure_stream("LOCAL_POSITION_NED", 3.0f * rate_mult); - configure_stream("RC_CHANNELS_RAW", 1.0f * rate_mult); - configure_stream("NAMED_VALUE_FLOAT", 1.0f * rate_mult); - configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f * rate_mult); - configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f * rate_mult); + configure_stream("HIGHRES_IMU", 1.0f); + configure_stream("ATTITUDE", 10.0f); + configure_stream("VFR_HUD", 8.0f); + configure_stream("GPS_RAW_INT", 1.0f); + configure_stream("GLOBAL_POSITION_INT", 3.0f); + configure_stream("LOCAL_POSITION_NED", 3.0f); + configure_stream("RC_CHANNELS_RAW", 1.0f); + configure_stream("NAMED_VALUE_FLOAT", 1.0f); + configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f); + configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f); configure_stream("DISTANCE_SENSOR", 0.5f); break; case MAVLINK_MODE_CAMERA: configure_stream("SYS_STATUS", 1.0f); - configure_stream("ATTITUDE", 15.0f * rate_mult); - configure_stream("GLOBAL_POSITION_INT", 15.0f * rate_mult); + configure_stream("ATTITUDE", 15.0f); + configure_stream("GLOBAL_POSITION_INT", 15.0f); configure_stream("CAMERA_CAPTURE", 1.0f); break; @@ -1488,10 +1356,12 @@ Mavlink::task_main(int argc, char *argv[]) /* don't send parameters on startup without request */ _mavlink_param_queue_index = param_count(); - MavlinkRateLimiter fast_rate_limiter(30000.0f / rate_mult); + float base_rate_mult = _datarate / 1000.0f; + + MavlinkRateLimiter fast_rate_limiter(30000.0f / base_rate_mult); /* set main loop delay depending on data rate to minimize CPU overhead */ - _main_loop_delay = MAIN_LOOP_DELAY / rate_mult; + _main_loop_delay = MAIN_LOOP_DELAY / base_rate_mult; /* now the instance is fully initialized and we can bump the instance count */ LL_APPEND(_mavlink_instances, this); @@ -1543,18 +1413,9 @@ Mavlink::task_main(int argc, char *argv[]) } if (fast_rate_limiter.check(t)) { + _mission_manager->eventloop(); - /* only send messages if they fit the buffer */ - if (check_can_send(0, MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { - mavlink_pm_queued_send(); - } - - if (check_can_send(0, MAVLINK_MSG_ID_MISSION_ITEM_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { - _mission_manager->eventloop(); - } - - if (!mavlink_logbuffer_is_empty(&_logbuffer) && - check_can_send(0, MAVLINK_MSG_ID_STATUSTEXT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES)) { + if (!mavlink_logbuffer_is_empty(&_logbuffer)) { struct mavlink_logmessage msg; int lb_ret = mavlink_logbuffer_read(&_logbuffer, &msg); @@ -1630,6 +1491,7 @@ Mavlink::task_main(int argc, char *argv[]) } delete _mission_manager; + delete _parameters_manager; delete _subscribe_to_stream; _subscribe_to_stream = nullptr; diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 1c62b03d2..7fcbae72e 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -58,7 +58,7 @@ #include "mavlink_stream.h" #include "mavlink_messages.h" #include "mavlink_mission.h" - +#include "mavlink_parameters.h" class Mavlink { @@ -160,11 +160,7 @@ public: */ int set_hil_enabled(bool hil_enabled); - bool check_can_send(const int prio, const unsigned packet_len); - - void send_message(const uint8_t msgid, const void *msg, const int prio); - - void send_message(const mavlink_message_t *msg); + void send_message(const uint8_t msgid, const void *msg); void handle_message(const mavlink_message_t *msg); @@ -285,6 +281,7 @@ private: MavlinkStream *_streams; MavlinkMissionManager *_mission_manager; + MavlinkParametersManager *_parameters_manager; orb_advert_t _mission_pub; int _mission_result_sub; @@ -305,6 +302,7 @@ private: int _baudrate; int _datarate; ///< data rate for normal streams (attitude, position, etc.) int _datarate_events; ///< data rate for params, waypoints, text messages + float _rate_mult; /** * If the queue index is not at 0, the queue sending @@ -352,51 +350,12 @@ private: perf_counter_t _loop_perf; /**< loop performance counter */ perf_counter_t _txerr_perf; /**< TX error counter */ - /** - * Send one parameter. - * - * @param param The parameter id to send. - * @return zero on success, nonzero on failure. - */ - int mavlink_pm_send_param(param_t param); - - /** - * Send one parameter identified by index. - * - * @param index The index of the parameter to send. - * @return zero on success, nonzero else. - */ - int mavlink_pm_send_param_for_index(uint16_t index); - - /** - * Send one parameter identified by name. - * - * @param name The index of the parameter to send. - * @return zero on success, nonzero else. - */ - int mavlink_pm_send_param_for_name(const char *name); - - /** - * Send a queue of parameters, one parameter per function call. - * - * @return zero on success, nonzero on failure - */ - int mavlink_pm_queued_send(void); - - /** - * Start sending the parameter queue. - * - * This function will not directly send parameters, but instead - * activate the sending of one parameter on each call of - * mavlink_pm_queued_send(). - * @see mavlink_pm_queued_send() - */ - void mavlink_pm_start_queued_send(); - void mavlink_update_system(); int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb); + static unsigned int interval_from_rate(float rate); + int configure_stream(const char *stream_name, const float rate); /** @@ -420,6 +379,11 @@ private: void pass_message(const mavlink_message_t *msg); + /** + * Update rate mult so total bitrate will be equal to _datarate. + */ + void update_rate_mult(); + static int mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg); /** diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index fe33985d2..7dc3ebac1 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -76,7 +76,7 @@ #include #include "mavlink_messages.h" - +#include "mavlink_main.h" static uint16_t cm_uint16_from_m_float(float m); static void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_setpoint_triplet_s *pos_sp_triplet, @@ -254,6 +254,15 @@ public: return new MavlinkStreamHeartbeat(mavlink); } + unsigned get_size() + { + return MAVLINK_MSG_ID_HEARTBEAT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + + bool const_rate() { + return true; + } + private: MavlinkOrbSubscription *status_sub; MavlinkOrbSubscription *pos_sp_triplet_sub; @@ -291,6 +300,7 @@ protected: } mavlink_heartbeat_t msg; + msg.base_mode = 0; msg.custom_mode = 0; get_mavlink_mode_state(&status, &pos_sp_triplet, &msg.system_status, &msg.base_mode, &msg.custom_mode); @@ -298,7 +308,7 @@ protected: msg.autopilot = mavlink_system.type; msg.mavlink_version = 3; - _mavlink->send_message(MAVLINK_MSG_ID_HEARTBEAT, &msg, 1); + _mavlink->send_message(MAVLINK_MSG_ID_HEARTBEAT, &msg); } }; @@ -311,7 +321,7 @@ public: return MavlinkStreamSysStatus::get_name_static(); } - static const char *get_name_static () + static const char *get_name_static() { return "SYS_STATUS"; } @@ -321,9 +331,14 @@ public: return MAVLINK_MSG_ID_SYS_STATUS; } - static MavlinkStream *new_instance() + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamSysStatus(mavlink); + } + + unsigned get_size() { - return new MavlinkStreamSysStatus(); + return MAVLINK_MSG_ID_SYS_STATUS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; } private: @@ -334,13 +349,13 @@ private: MavlinkStreamSysStatus& operator = (const MavlinkStreamSysStatus &); protected: - explicit MavlinkStreamSysStatus() : MavlinkStream(), + explicit MavlinkStreamSysStatus(Mavlink *mavlink) : MavlinkStream(mavlink), status_sub(nullptr) {} - void subscribe(Mavlink *mavlink) + void subscribe() { - status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); + status_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); } void send(const hrt_abstime t) @@ -348,1591 +363,1594 @@ protected: struct vehicle_status_s status; if (status_sub->update(&status)) { - mavlink_msg_sys_status_send(_channel, - status.onboard_control_sensors_present, - status.onboard_control_sensors_enabled, - status.onboard_control_sensors_health, - status.load * 1000.0f, - status.battery_voltage * 1000.0f, - status.battery_current * 100.0f, - status.battery_remaining * 100.0f, - status.drop_rate_comm, - status.errors_comm, - status.errors_count1, - status.errors_count2, - status.errors_count3, - status.errors_count4); - } - } -}; - - -class MavlinkStreamHighresIMU : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamHighresIMU::get_name_static(); - } - - static const char *get_name_static() - { - return "HIGHRES_IMU"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_HIGHRES_IMU; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamHighresIMU(); - } - -private: - MavlinkOrbSubscription *sensor_sub; - uint64_t sensor_time; - - uint64_t accel_timestamp; - uint64_t gyro_timestamp; - uint64_t mag_timestamp; - uint64_t baro_timestamp; - - /* do not allow top copying this class */ - MavlinkStreamHighresIMU(MavlinkStreamHighresIMU &); - MavlinkStreamHighresIMU& operator = (const MavlinkStreamHighresIMU &); - -protected: - explicit MavlinkStreamHighresIMU() : MavlinkStream(), - sensor_sub(nullptr), - sensor_time(0), - accel_timestamp(0), - gyro_timestamp(0), - mag_timestamp(0), - baro_timestamp(0) - {} - - void subscribe(Mavlink *mavlink) - { - sensor_sub = mavlink->add_orb_subscription(ORB_ID(sensor_combined)); - } - - void send(const hrt_abstime t) - { - struct sensor_combined_s sensor; - - if (sensor_sub->update(&sensor_time, &sensor)) { - uint16_t fields_updated = 0; - - if (accel_timestamp != sensor.accelerometer_timestamp) { - /* mark first three dimensions as changed */ - fields_updated |= (1 << 0) | (1 << 1) | (1 << 2); - accel_timestamp = sensor.accelerometer_timestamp; - } - - if (gyro_timestamp != sensor.timestamp) { - /* mark second group dimensions as changed */ - fields_updated |= (1 << 3) | (1 << 4) | (1 << 5); - gyro_timestamp = sensor.timestamp; - } - - if (mag_timestamp != sensor.magnetometer_timestamp) { - /* mark third group dimensions as changed */ - fields_updated |= (1 << 6) | (1 << 7) | (1 << 8); - mag_timestamp = sensor.magnetometer_timestamp; - } - - if (baro_timestamp != sensor.baro_timestamp) { - /* mark last group dimensions as changed */ - fields_updated |= (1 << 9) | (1 << 11) | (1 << 12); - baro_timestamp = sensor.baro_timestamp; - } - - mavlink_msg_highres_imu_send(_channel, - sensor.timestamp, - sensor.accelerometer_m_s2[0], sensor.accelerometer_m_s2[1], sensor.accelerometer_m_s2[2], - sensor.gyro_rad_s[0], sensor.gyro_rad_s[1], sensor.gyro_rad_s[2], - sensor.magnetometer_ga[0], sensor.magnetometer_ga[1], sensor.magnetometer_ga[2], - sensor.baro_pres_mbar, sensor.differential_pressure_pa, - sensor.baro_alt_meter, sensor.baro_temp_celcius, - fields_updated); - } - } -}; - - -class MavlinkStreamAttitude : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamAttitude::get_name_static(); - } - - static const char *get_name_static() - { - return "ATTITUDE"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_ATTITUDE; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamAttitude(); - } - -private: - MavlinkOrbSubscription *att_sub; - uint64_t att_time; - - /* do not allow top copying this class */ - MavlinkStreamAttitude(MavlinkStreamAttitude &); - MavlinkStreamAttitude& operator = (const MavlinkStreamAttitude &); - - -protected: - explicit MavlinkStreamAttitude() : MavlinkStream(), - att_sub(nullptr), - att_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); - } - - void send(const hrt_abstime t) - { - struct vehicle_attitude_s att; - - if (att_sub->update(&att_time, &att)) { - mavlink_msg_attitude_send(_channel, - att.timestamp / 1000, - att.roll, att.pitch, att.yaw, - att.rollspeed, att.pitchspeed, att.yawspeed); - } - } -}; - - -class MavlinkStreamAttitudeQuaternion : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamAttitudeQuaternion::get_name_static(); - } - - static const char *get_name_static() - { - return "ATTITUDE_QUATERNION"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_ATTITUDE_QUATERNION; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamAttitudeQuaternion(); - } - -private: - MavlinkOrbSubscription *att_sub; - uint64_t att_time; - - /* do not allow top copying this class */ - MavlinkStreamAttitudeQuaternion(MavlinkStreamAttitudeQuaternion &); - MavlinkStreamAttitudeQuaternion& operator = (const MavlinkStreamAttitudeQuaternion &); - -protected: - explicit MavlinkStreamAttitudeQuaternion() : MavlinkStream(), - att_sub(nullptr), - att_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); - } - - void send(const hrt_abstime t) - { - struct vehicle_attitude_s att; - - if (att_sub->update(&att_time, &att)) { - mavlink_msg_attitude_quaternion_send(_channel, - att.timestamp / 1000, - att.q[0], - att.q[1], - att.q[2], - att.q[3], - att.rollspeed, - att.pitchspeed, - att.yawspeed); - } - } -}; - - -class MavlinkStreamVFRHUD : public MavlinkStream -{ -public: - - const char *get_name() const - { - return MavlinkStreamVFRHUD::get_name_static(); - } - - static const char *get_name_static() - { - return "VFR_HUD"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_VFR_HUD; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamVFRHUD(); - } - -private: - MavlinkOrbSubscription *att_sub; - uint64_t att_time; - - MavlinkOrbSubscription *pos_sub; - uint64_t pos_time; - - MavlinkOrbSubscription *armed_sub; - uint64_t armed_time; - - MavlinkOrbSubscription *act_sub; - uint64_t act_time; - - MavlinkOrbSubscription *airspeed_sub; - uint64_t airspeed_time; - - /* do not allow top copying this class */ - MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &); - MavlinkStreamVFRHUD& operator = (const MavlinkStreamVFRHUD &); - -protected: - explicit MavlinkStreamVFRHUD() : MavlinkStream(), - att_sub(nullptr), - att_time(0), - pos_sub(nullptr), - pos_time(0), - armed_sub(nullptr), - armed_time(0), - act_sub(nullptr), - act_time(0), - airspeed_sub(nullptr), - airspeed_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); - pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); - armed_sub = mavlink->add_orb_subscription(ORB_ID(actuator_armed)); - act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_controls_0)); - airspeed_sub = mavlink->add_orb_subscription(ORB_ID(airspeed)); - } - - void send(const hrt_abstime t) - { - struct vehicle_attitude_s att; - struct vehicle_global_position_s pos; - struct actuator_armed_s armed; - struct actuator_controls_s act; - struct airspeed_s airspeed; - - bool updated = att_sub->update(&att_time, &att); - updated |= pos_sub->update(&pos_time, &pos); - updated |= armed_sub->update(&armed_time, &armed); - updated |= act_sub->update(&act_time, &act); - updated |= airspeed_sub->update(&airspeed_time, &airspeed); - - if (updated) { - float groundspeed = sqrtf(pos.vel_n * pos.vel_n + pos.vel_e * pos.vel_e); - uint16_t heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F; - float throttle = armed.armed ? act.control[3] * 100.0f : 0.0f; - - mavlink_msg_vfr_hud_send(_channel, - airspeed.true_airspeed_m_s, - groundspeed, - heading, - throttle, - pos.alt, - -pos.vel_d); - } - } -}; - - -class MavlinkStreamGPSRawInt : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamGPSRawInt::get_name_static(); - } - - static const char *get_name_static() - { - return "GPS_RAW_INT"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_GPS_RAW_INT; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamGPSRawInt(); - } - -private: - MavlinkOrbSubscription *gps_sub; - uint64_t gps_time; - - /* do not allow top copying this class */ - MavlinkStreamGPSRawInt(MavlinkStreamGPSRawInt &); - MavlinkStreamGPSRawInt& operator = (const MavlinkStreamGPSRawInt &); - -protected: - explicit MavlinkStreamGPSRawInt() : MavlinkStream(), - gps_sub(nullptr), - gps_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - gps_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position)); - } - - void send(const hrt_abstime t) - { - struct vehicle_gps_position_s gps; - - if (gps_sub->update(&gps_time, &gps)) { - mavlink_msg_gps_raw_int_send(_channel, - gps.timestamp_position, - gps.fix_type, - gps.lat, - gps.lon, - gps.alt, - cm_uint16_from_m_float(gps.eph), - cm_uint16_from_m_float(gps.epv), - gps.vel_m_s * 100.0f, - _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f, - gps.satellites_used); + mavlink_sys_status_t msg; + + msg.onboard_control_sensors_present = status.onboard_control_sensors_present; + msg.onboard_control_sensors_enabled = status.onboard_control_sensors_enabled; + msg.onboard_control_sensors_health = status.onboard_control_sensors_health; + msg.load = status.load * 1000.0f; + msg.voltage_battery = status.battery_voltage * 1000.0f; + msg.current_battery = status.battery_current * 100.0f; + msg.drop_rate_comm = status.drop_rate_comm; + msg.errors_comm = status.errors_comm; + msg.errors_count1 = status.errors_count1; + msg.errors_count2 = status.errors_count2; + msg.errors_count3 = status.errors_count3; + msg.errors_count4 = status.errors_count4; + msg.battery_remaining = status.battery_remaining * 100.0f; + + _mavlink->send_message(MAVLINK_MSG_ID_SYS_STATUS, &msg); } } }; -class MavlinkStreamGlobalPositionInt : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamGlobalPositionInt::get_name_static(); - } - - static const char *get_name_static() - { - return "GLOBAL_POSITION_INT"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_GLOBAL_POSITION_INT; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamGlobalPositionInt(); - } - -private: - MavlinkOrbSubscription *pos_sub; - uint64_t pos_time; - - MavlinkOrbSubscription *home_sub; - uint64_t home_time; - - /* do not allow top copying this class */ - MavlinkStreamGlobalPositionInt(MavlinkStreamGlobalPositionInt &); - MavlinkStreamGlobalPositionInt& operator = (const MavlinkStreamGlobalPositionInt &); - -protected: - explicit MavlinkStreamGlobalPositionInt() : MavlinkStream(), - pos_sub(nullptr), - pos_time(0), - home_sub(nullptr), - home_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); - home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); - } - - void send(const hrt_abstime t) - { - struct vehicle_global_position_s pos; - struct home_position_s home; - - bool updated = pos_sub->update(&pos_time, &pos); - updated |= home_sub->update(&home_time, &home); - - if (updated) { - mavlink_msg_global_position_int_send(_channel, - pos.timestamp / 1000, - pos.lat * 1e7, - pos.lon * 1e7, - pos.alt * 1000.0f, - (pos.alt - home.alt) * 1000.0f, - pos.vel_n * 100.0f, - pos.vel_e * 100.0f, - pos.vel_d * 100.0f, - _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f); - } - } -}; - - -class MavlinkStreamLocalPositionNED : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamLocalPositionNED::get_name_static(); - } - - static const char *get_name_static() - { - return "LOCAL_POSITION_NED"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_LOCAL_POSITION_NED; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamLocalPositionNED(); - } - -private: - MavlinkOrbSubscription *pos_sub; - uint64_t pos_time; - - /* do not allow top copying this class */ - MavlinkStreamLocalPositionNED(MavlinkStreamLocalPositionNED &); - MavlinkStreamLocalPositionNED& operator = (const MavlinkStreamLocalPositionNED &); - -protected: - explicit MavlinkStreamLocalPositionNED() : MavlinkStream(), - pos_sub(nullptr), - pos_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position)); - } - - void send(const hrt_abstime t) - { - struct vehicle_local_position_s pos; - - if (pos_sub->update(&pos_time, &pos)) { - mavlink_msg_local_position_ned_send(_channel, - pos.timestamp / 1000, - pos.x, - pos.y, - pos.z, - pos.vx, - pos.vy, - pos.vz); - } - } -}; - - - -class MavlinkStreamViconPositionEstimate : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamViconPositionEstimate::get_name_static(); - } - - static const char *get_name_static() - { - return "VICON_POSITION_ESTIMATE"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamViconPositionEstimate(); - } - -private: - MavlinkOrbSubscription *pos_sub; - uint64_t pos_time; - - /* do not allow top copying this class */ - MavlinkStreamViconPositionEstimate(MavlinkStreamViconPositionEstimate &); - MavlinkStreamViconPositionEstimate& operator = (const MavlinkStreamViconPositionEstimate &); - -protected: - explicit MavlinkStreamViconPositionEstimate() : MavlinkStream(), - pos_sub(nullptr), - pos_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position)); - } - - void send(const hrt_abstime t) - { - struct vehicle_vicon_position_s pos; - - if (pos_sub->update(&pos_time, &pos)) { - mavlink_msg_vicon_position_estimate_send(_channel, - pos.timestamp / 1000, - pos.x, - pos.y, - pos.z, - pos.roll, - pos.pitch, - pos.yaw); - } - } -}; - - -class MavlinkStreamGPSGlobalOrigin : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamGPSGlobalOrigin::get_name_static(); - } - - static const char *get_name_static() - { - return "GPS_GLOBAL_ORIGIN"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamGPSGlobalOrigin(); - } - -private: - MavlinkOrbSubscription *home_sub; - - /* do not allow top copying this class */ - MavlinkStreamGPSGlobalOrigin(MavlinkStreamGPSGlobalOrigin &); - MavlinkStreamGPSGlobalOrigin& operator = (const MavlinkStreamGPSGlobalOrigin &); - -protected: - explicit MavlinkStreamGPSGlobalOrigin() : MavlinkStream(), - home_sub(nullptr) - {} - - void subscribe(Mavlink *mavlink) - { - home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); - } - - void send(const hrt_abstime t) - { - /* we're sending the GPS home periodically to ensure the - * the GCS does pick it up at one point */ - if (home_sub->is_published()) { - struct home_position_s home; - - if (home_sub->update(&home)) { - mavlink_msg_gps_global_origin_send(_channel, - (int32_t)(home.lat * 1e7), - (int32_t)(home.lon * 1e7), - (int32_t)(home.alt) * 1000.0f); - } - } - } -}; - -template -class MavlinkStreamServoOutputRaw : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamServoOutputRaw::get_name_static(); - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; - } - - static const char *get_name_static() - { - switch (N) { - case 0: - return "SERVO_OUTPUT_RAW_0"; - - case 1: - return "SERVO_OUTPUT_RAW_1"; - - case 2: - return "SERVO_OUTPUT_RAW_2"; - - case 3: - return "SERVO_OUTPUT_RAW_3"; - } - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamServoOutputRaw(); - } - -private: - MavlinkOrbSubscription *act_sub; - uint64_t act_time; - - /* do not allow top copying this class */ - MavlinkStreamServoOutputRaw(MavlinkStreamServoOutputRaw &); - MavlinkStreamServoOutputRaw& operator = (const MavlinkStreamServoOutputRaw &); - -protected: - explicit MavlinkStreamServoOutputRaw() : MavlinkStream(), - act_sub(nullptr), - act_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - orb_id_t act_topics[] = { - ORB_ID(actuator_outputs_0), - ORB_ID(actuator_outputs_1), - ORB_ID(actuator_outputs_2), - ORB_ID(actuator_outputs_3) - }; - - act_sub = mavlink->add_orb_subscription(act_topics[N]); - } - - void send(const hrt_abstime t) - { - struct actuator_outputs_s act; - - if (act_sub->update(&act_time, &act)) { - mavlink_msg_servo_output_raw_send(_channel, - act.timestamp / 1000, - N, - act.output[0], - act.output[1], - act.output[2], - act.output[3], - act.output[4], - act.output[5], - act.output[6], - act.output[7]); - } - } -}; - - -class MavlinkStreamHILControls : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamHILControls::get_name_static(); - } - - static const char *get_name_static() - { - return "HIL_CONTROLS"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_HIL_CONTROLS; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamHILControls(); - } - -private: - MavlinkOrbSubscription *status_sub; - uint64_t status_time; - - MavlinkOrbSubscription *pos_sp_triplet_sub; - uint64_t pos_sp_triplet_time; - - MavlinkOrbSubscription *act_sub; - uint64_t act_time; - - /* do not allow top copying this class */ - MavlinkStreamHILControls(MavlinkStreamHILControls &); - MavlinkStreamHILControls& operator = (const MavlinkStreamHILControls &); - -protected: - explicit MavlinkStreamHILControls() : MavlinkStream(), - status_sub(nullptr), - status_time(0), - pos_sp_triplet_sub(nullptr), - pos_sp_triplet_time(0), - act_sub(nullptr), - act_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); - pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); - act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0)); - } - - void send(const hrt_abstime t) - { - struct vehicle_status_s status; - struct position_setpoint_triplet_s pos_sp_triplet; - struct actuator_outputs_s act; - - bool updated = act_sub->update(&act_time, &act); - updated |= pos_sp_triplet_sub->update(&pos_sp_triplet_time, &pos_sp_triplet); - updated |= status_sub->update(&status_time, &status); - - if (updated && (status.arming_state == ARMING_STATE_ARMED)) { - /* translate the current syste state to mavlink state and mode */ - uint8_t mavlink_state; - uint8_t mavlink_base_mode; - uint32_t mavlink_custom_mode; - get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode); - - float out[8]; - - const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2; - - /* scale outputs depending on system type */ - if (mavlink_system.type == MAV_TYPE_QUADROTOR || - mavlink_system.type == MAV_TYPE_HEXAROTOR || - mavlink_system.type == MAV_TYPE_OCTOROTOR) { - /* multirotors: set number of rotor outputs depending on type */ - - unsigned n; - - switch (mavlink_system.type) { - case MAV_TYPE_QUADROTOR: - n = 4; - break; - - case MAV_TYPE_HEXAROTOR: - n = 6; - break; - - default: - n = 8; - break; - } - - for (unsigned i = 0; i < 8; i++) { - if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) { - if (i < n) { - /* scale PWM out 900..2100 us to 0..1 for rotors */ - out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); - - } else { - /* scale PWM out 900..2100 us to -1..1 for other channels */ - out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); - } - - } else { - /* send 0 when disarmed */ - out[i] = 0.0f; - } - } - - } else { - /* fixed wing: scale throttle to 0..1 and other channels to -1..1 */ - - for (unsigned i = 0; i < 8; i++) { - if (i != 3) { - /* scale PWM out 900..2100 us to -1..1 for normal channels */ - out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); - - } else { - /* scale PWM out 900..2100 us to 0..1 for throttle */ - out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); - } - - } - } - - mavlink_msg_hil_controls_send(_channel, - hrt_absolute_time(), - out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7], - mavlink_base_mode, - 0); - } - } -}; - - -class MavlinkStreamGlobalPositionSetpointInt : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamGlobalPositionSetpointInt::get_name_static(); - } - - static const char *get_name_static() - { - return "GLOBAL_POSITION_SETPOINT_INT"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamGlobalPositionSetpointInt(); - } - -private: - MavlinkOrbSubscription *pos_sp_triplet_sub; - - /* do not allow top copying this class */ - MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &); - MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &); - -protected: - explicit MavlinkStreamGlobalPositionSetpointInt() : MavlinkStream(), - pos_sp_triplet_sub(nullptr) - {} - - void subscribe(Mavlink *mavlink) - { - pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); - } - - void send(const hrt_abstime t) - { - struct position_setpoint_triplet_s pos_sp_triplet; - - if (pos_sp_triplet_sub->update(&pos_sp_triplet)) { - mavlink_msg_global_position_setpoint_int_send(_channel, - MAV_FRAME_GLOBAL, - (int32_t)(pos_sp_triplet.current.lat * 1e7), - (int32_t)(pos_sp_triplet.current.lon * 1e7), - (int32_t)(pos_sp_triplet.current.alt * 1000), - (int16_t)(pos_sp_triplet.current.yaw * M_RAD_TO_DEG_F * 100.0f)); - } - } -}; - - -class MavlinkStreamLocalPositionSetpoint : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamLocalPositionSetpoint::get_name_static(); - } - - static const char *get_name_static() - { - return "LOCAL_POSITION_SETPOINT"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamLocalPositionSetpoint(); - } - -private: - MavlinkOrbSubscription *pos_sp_sub; - uint64_t pos_sp_time; - - /* do not allow top copying this class */ - MavlinkStreamLocalPositionSetpoint(MavlinkStreamLocalPositionSetpoint &); - MavlinkStreamLocalPositionSetpoint& operator = (const MavlinkStreamLocalPositionSetpoint &); - -protected: - explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(), - pos_sp_sub(nullptr), - pos_sp_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - pos_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint)); - } - - void send(const hrt_abstime t) - { - struct vehicle_local_position_setpoint_s pos_sp; - - if (pos_sp_sub->update(&pos_sp_time, &pos_sp)) { - mavlink_msg_local_position_setpoint_send(_channel, - MAV_FRAME_LOCAL_NED, - pos_sp.x, - pos_sp.y, - pos_sp.z, - pos_sp.yaw); - } - } -}; - - -class MavlinkStreamRollPitchYawThrustSetpoint : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamRollPitchYawThrustSetpoint::get_name_static(); - } - - static const char *get_name_static() - { - return "ROLL_PITCH_YAW_THRUST_SETPOINT"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamRollPitchYawThrustSetpoint(); - } - -private: - MavlinkOrbSubscription *att_sp_sub; - uint64_t att_sp_time; - - /* do not allow top copying this class */ - MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &); - MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &); - -protected: - explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(), - att_sp_sub(nullptr), - att_sp_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - att_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint)); - } - - void send(const hrt_abstime t) - { - struct vehicle_attitude_setpoint_s att_sp; - - if (att_sp_sub->update(&att_sp_time, &att_sp)) { - mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(_channel, - att_sp.timestamp / 1000, - att_sp.roll_body, - att_sp.pitch_body, - att_sp.yaw_body, - att_sp.thrust); - } - } -}; - - -class MavlinkStreamRollPitchYawRatesThrustSetpoint : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static(); - } - - static const char *get_name_static() - { - return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamRollPitchYawRatesThrustSetpoint(); - } - -private: - MavlinkOrbSubscription *att_rates_sp_sub; - uint64_t att_rates_sp_time; - - /* do not allow top copying this class */ - MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &); - MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &); - -protected: - explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(), - att_rates_sp_sub(nullptr), - att_rates_sp_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - att_rates_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint)); - } - - void send(const hrt_abstime t) - { - struct vehicle_rates_setpoint_s att_rates_sp; - - if (att_rates_sp_sub->update(&att_rates_sp_time, &att_rates_sp)) { - mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(_channel, - att_rates_sp.timestamp / 1000, - att_rates_sp.roll, - att_rates_sp.pitch, - att_rates_sp.yaw, - att_rates_sp.thrust); - } - } -}; - - -class MavlinkStreamRCChannelsRaw : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamRCChannelsRaw::get_name_static(); - } - - static const char *get_name_static() - { - return "RC_CHANNELS_RAW"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_RC_CHANNELS_RAW; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamRCChannelsRaw(); - } - -private: - MavlinkOrbSubscription *rc_sub; - uint64_t rc_time; - - /* do not allow top copying this class */ - MavlinkStreamRCChannelsRaw(MavlinkStreamRCChannelsRaw &); - MavlinkStreamRCChannelsRaw& operator = (const MavlinkStreamRCChannelsRaw &); - -protected: - explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(), - rc_sub(nullptr), - rc_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - rc_sub = mavlink->add_orb_subscription(ORB_ID(input_rc)); - } - - void send(const hrt_abstime t) - { - struct rc_input_values rc; - - if (rc_sub->update(&rc_time, &rc)) { - const unsigned port_width = 8; - - // Deprecated message (but still needed for compatibility!) - for (unsigned i = 0; (i * port_width) < rc.channel_count; i++) { - /* Channels are sent in MAVLink main loop at a fixed interval */ - mavlink_msg_rc_channels_raw_send(_channel, - rc.timestamp_publication / 1000, - i, - (rc.channel_count > (i * port_width) + 0) ? rc.values[(i * port_width) + 0] : UINT16_MAX, - (rc.channel_count > (i * port_width) + 1) ? rc.values[(i * port_width) + 1] : UINT16_MAX, - (rc.channel_count > (i * port_width) + 2) ? rc.values[(i * port_width) + 2] : UINT16_MAX, - (rc.channel_count > (i * port_width) + 3) ? rc.values[(i * port_width) + 3] : UINT16_MAX, - (rc.channel_count > (i * port_width) + 4) ? rc.values[(i * port_width) + 4] : UINT16_MAX, - (rc.channel_count > (i * port_width) + 5) ? rc.values[(i * port_width) + 5] : UINT16_MAX, - (rc.channel_count > (i * port_width) + 6) ? rc.values[(i * port_width) + 6] : UINT16_MAX, - (rc.channel_count > (i * port_width) + 7) ? rc.values[(i * port_width) + 7] : UINT16_MAX, - rc.rssi); - } - - // New message - mavlink_msg_rc_channels_send(_channel, - rc.timestamp_publication / 1000, - rc.channel_count, - ((rc.channel_count > 0) ? rc.values[0] : UINT16_MAX), - ((rc.channel_count > 1) ? rc.values[1] : UINT16_MAX), - ((rc.channel_count > 2) ? rc.values[2] : UINT16_MAX), - ((rc.channel_count > 3) ? rc.values[3] : UINT16_MAX), - ((rc.channel_count > 4) ? rc.values[4] : UINT16_MAX), - ((rc.channel_count > 5) ? rc.values[5] : UINT16_MAX), - ((rc.channel_count > 6) ? rc.values[6] : UINT16_MAX), - ((rc.channel_count > 7) ? rc.values[7] : UINT16_MAX), - ((rc.channel_count > 8) ? rc.values[8] : UINT16_MAX), - ((rc.channel_count > 9) ? rc.values[9] : UINT16_MAX), - ((rc.channel_count > 10) ? rc.values[10] : UINT16_MAX), - ((rc.channel_count > 11) ? rc.values[11] : UINT16_MAX), - ((rc.channel_count > 12) ? rc.values[12] : UINT16_MAX), - ((rc.channel_count > 13) ? rc.values[13] : UINT16_MAX), - ((rc.channel_count > 14) ? rc.values[14] : UINT16_MAX), - ((rc.channel_count > 15) ? rc.values[15] : UINT16_MAX), - ((rc.channel_count > 16) ? rc.values[16] : UINT16_MAX), - ((rc.channel_count > 17) ? rc.values[17] : UINT16_MAX), - rc.rssi); - } - } -}; - - -class MavlinkStreamManualControl : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamManualControl::get_name_static(); - } - - static const char *get_name_static() - { - return "MANUAL_CONTROL"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_MANUAL_CONTROL; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamManualControl(); - } - -private: - MavlinkOrbSubscription *manual_sub; - uint64_t manual_time; - - /* do not allow top copying this class */ - MavlinkStreamManualControl(MavlinkStreamManualControl &); - MavlinkStreamManualControl& operator = (const MavlinkStreamManualControl &); - -protected: - explicit MavlinkStreamManualControl() : MavlinkStream(), - manual_sub(nullptr), - manual_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - manual_sub = mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); - } - - void send(const hrt_abstime t) - { - struct manual_control_setpoint_s manual; - - if (manual_sub->update(&manual_time, &manual)) { - mavlink_msg_manual_control_send(_channel, - mavlink_system.sysid, - manual.x * 1000, - manual.y * 1000, - manual.z * 1000, - manual.r * 1000, - 0); - } - } -}; - - -class MavlinkStreamOpticalFlow : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamOpticalFlow::get_name_static(); - } - - static const char *get_name_static() - { - return "OPTICAL_FLOW"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_OPTICAL_FLOW; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamOpticalFlow(); - } - -private: - MavlinkOrbSubscription *flow_sub; - uint64_t flow_time; - - /* do not allow top copying this class */ - MavlinkStreamOpticalFlow(MavlinkStreamOpticalFlow &); - MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &); - -protected: - explicit MavlinkStreamOpticalFlow() : MavlinkStream(), - flow_sub(nullptr), - flow_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - flow_sub = mavlink->add_orb_subscription(ORB_ID(optical_flow)); - } - - void send(const hrt_abstime t) - { - struct optical_flow_s flow; - - if (flow_sub->update(&flow_time, &flow)) { - mavlink_msg_optical_flow_send(_channel, - flow.timestamp, - flow.sensor_id, - flow.flow_raw_x, flow.flow_raw_y, - flow.flow_comp_x_m, flow.flow_comp_y_m, - flow.quality, - flow.ground_distance_m); - } - } -}; - -class MavlinkStreamAttitudeControls : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamAttitudeControls::get_name_static(); - } - - static const char *get_name_static() - { - return "ATTITUDE_CONTROLS"; - } - - uint8_t get_id() - { - return 0; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamAttitudeControls(); - } - -private: - MavlinkOrbSubscription *att_ctrl_sub; - uint64_t att_ctrl_time; - - /* do not allow top copying this class */ - MavlinkStreamAttitudeControls(MavlinkStreamAttitudeControls &); - MavlinkStreamAttitudeControls& operator = (const MavlinkStreamAttitudeControls &); - -protected: - explicit MavlinkStreamAttitudeControls() : MavlinkStream(), - att_ctrl_sub(nullptr), - att_ctrl_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - att_ctrl_sub = mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); - } - - void send(const hrt_abstime t) - { - struct actuator_controls_s att_ctrl; - - if (att_ctrl_sub->update(&att_ctrl_time, &att_ctrl)) { - /* send, add spaces so that string buffer is at least 10 chars long */ - mavlink_msg_named_value_float_send(_channel, - att_ctrl.timestamp / 1000, - "rll ctrl ", - att_ctrl.control[0]); - mavlink_msg_named_value_float_send(_channel, - att_ctrl.timestamp / 1000, - "ptch ctrl ", - att_ctrl.control[1]); - mavlink_msg_named_value_float_send(_channel, - att_ctrl.timestamp / 1000, - "yaw ctrl ", - att_ctrl.control[2]); - mavlink_msg_named_value_float_send(_channel, - att_ctrl.timestamp / 1000, - "thr ctrl ", - att_ctrl.control[3]); - } - } -}; - -class MavlinkStreamNamedValueFloat : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamNamedValueFloat::get_name_static(); - } - - static const char *get_name_static() - { - return "NAMED_VALUE_FLOAT"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamNamedValueFloat(); - } - -private: - MavlinkOrbSubscription *debug_sub; - uint64_t debug_time; - - /* do not allow top copying this class */ - MavlinkStreamNamedValueFloat(MavlinkStreamNamedValueFloat &); - MavlinkStreamNamedValueFloat& operator = (const MavlinkStreamNamedValueFloat &); - -protected: - explicit MavlinkStreamNamedValueFloat() : MavlinkStream(), - debug_sub(nullptr), - debug_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - debug_sub = mavlink->add_orb_subscription(ORB_ID(debug_key_value)); - } - - void send(const hrt_abstime t) - { - struct debug_key_value_s debug; - - if (debug_sub->update(&debug_time, &debug)) { - /* enforce null termination */ - debug.key[sizeof(debug.key) - 1] = '\0'; - - mavlink_msg_named_value_float_send(_channel, - debug.timestamp_ms, - debug.key, - debug.value); - } - } -}; - -class MavlinkStreamCameraCapture : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamCameraCapture::get_name_static(); - } - - static const char *get_name_static() - { - return "CAMERA_CAPTURE"; - } - - uint8_t get_id() - { - return 0; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamCameraCapture(); - } - -private: - MavlinkOrbSubscription *status_sub; - - /* do not allow top copying this class */ - MavlinkStreamCameraCapture(MavlinkStreamCameraCapture &); - MavlinkStreamCameraCapture& operator = (const MavlinkStreamCameraCapture &); - -protected: - explicit MavlinkStreamCameraCapture() : MavlinkStream(), - status_sub(nullptr) - {} - - void subscribe(Mavlink *mavlink) - { - status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); - } - - void send(const hrt_abstime t) - { - struct vehicle_status_s status; - (void)status_sub->update(&status); - - if (status.arming_state == ARMING_STATE_ARMED - || status.arming_state == ARMING_STATE_ARMED_ERROR) { - - /* send camera capture on */ - mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0); - - } else { - /* send camera capture off */ - mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0); - } - } -}; - -class MavlinkStreamDistanceSensor : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamDistanceSensor::get_name_static(); - } - - static const char *get_name_static() - { - return "DISTANCE_SENSOR"; - } - - uint8_t get_id() - { - return MAVLINK_MSG_ID_DISTANCE_SENSOR; - } - - static MavlinkStream *new_instance() - { - return new MavlinkStreamDistanceSensor(); - } - -private: - MavlinkOrbSubscription *range_sub; - uint64_t range_time; - - /* do not allow top copying this class */ - MavlinkStreamDistanceSensor(MavlinkStreamDistanceSensor &); - MavlinkStreamDistanceSensor& operator = (const MavlinkStreamDistanceSensor &); - -protected: - explicit MavlinkStreamDistanceSensor() : MavlinkStream(), - range_sub(nullptr), - range_time(0) - {} - - void subscribe(Mavlink *mavlink) - { - range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder)); - } - - void send(const hrt_abstime t) - { - struct range_finder_report range; - - if (range_sub->update(&range_time, &range)) { - - uint8_t type; - - switch (range.type) { - case RANGE_FINDER_TYPE_LASER: - type = MAV_DISTANCE_SENSOR_LASER; - break; - } - - uint8_t id = 0; - uint8_t orientation = 0; - uint8_t covariance = 20; - - mavlink_msg_distance_sensor_send(_channel, range.timestamp / 1000, type, id, orientation, - range.minimum_distance*100, range.maximum_distance*100, range.distance*100, covariance); - } - } -}; +//class MavlinkStreamHighresIMU : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamHighresIMU::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "HIGHRES_IMU"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_HIGHRES_IMU; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamHighresIMU(); +// } +// +//private: +// MavlinkOrbSubscription *sensor_sub; +// uint64_t sensor_time; +// +// uint64_t accel_timestamp; +// uint64_t gyro_timestamp; +// uint64_t mag_timestamp; +// uint64_t baro_timestamp; +// +// /* do not allow top copying this class */ +// MavlinkStreamHighresIMU(MavlinkStreamHighresIMU &); +// MavlinkStreamHighresIMU& operator = (const MavlinkStreamHighresIMU &); +// +//protected: +// explicit MavlinkStreamHighresIMU() : MavlinkStream(), +// sensor_sub(nullptr), +// sensor_time(0), +// accel_timestamp(0), +// gyro_timestamp(0), +// mag_timestamp(0), +// baro_timestamp(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// sensor_sub = mavlink->add_orb_subscription(ORB_ID(sensor_combined)); +// } +// +// void send(const hrt_abstime t) +// { +// struct sensor_combined_s sensor; +// +// if (sensor_sub->update(&sensor_time, &sensor)) { +// uint16_t fields_updated = 0; +// +// if (accel_timestamp != sensor.accelerometer_timestamp) { +// /* mark first three dimensions as changed */ +// fields_updated |= (1 << 0) | (1 << 1) | (1 << 2); +// accel_timestamp = sensor.accelerometer_timestamp; +// } +// +// if (gyro_timestamp != sensor.timestamp) { +// /* mark second group dimensions as changed */ +// fields_updated |= (1 << 3) | (1 << 4) | (1 << 5); +// gyro_timestamp = sensor.timestamp; +// } +// +// if (mag_timestamp != sensor.magnetometer_timestamp) { +// /* mark third group dimensions as changed */ +// fields_updated |= (1 << 6) | (1 << 7) | (1 << 8); +// mag_timestamp = sensor.magnetometer_timestamp; +// } +// +// if (baro_timestamp != sensor.baro_timestamp) { +// /* mark last group dimensions as changed */ +// fields_updated |= (1 << 9) | (1 << 11) | (1 << 12); +// baro_timestamp = sensor.baro_timestamp; +// } +// +// mavlink_msg_highres_imu_send(_channel, +// sensor.timestamp, +// sensor.accelerometer_m_s2[0], sensor.accelerometer_m_s2[1], sensor.accelerometer_m_s2[2], +// sensor.gyro_rad_s[0], sensor.gyro_rad_s[1], sensor.gyro_rad_s[2], +// sensor.magnetometer_ga[0], sensor.magnetometer_ga[1], sensor.magnetometer_ga[2], +// sensor.baro_pres_mbar, sensor.differential_pressure_pa, +// sensor.baro_alt_meter, sensor.baro_temp_celcius, +// fields_updated); +// } +// } +//}; +// +// +//class MavlinkStreamAttitude : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamAttitude::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "ATTITUDE"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_ATTITUDE; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamAttitude(); +// } +// +//private: +// MavlinkOrbSubscription *att_sub; +// uint64_t att_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamAttitude(MavlinkStreamAttitude &); +// MavlinkStreamAttitude& operator = (const MavlinkStreamAttitude &); +// +// +//protected: +// explicit MavlinkStreamAttitude() : MavlinkStream(), +// att_sub(nullptr), +// att_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_attitude_s att; +// +// if (att_sub->update(&att_time, &att)) { +// mavlink_msg_attitude_send(_channel, +// att.timestamp / 1000, +// att.roll, att.pitch, att.yaw, +// att.rollspeed, att.pitchspeed, att.yawspeed); +// } +// } +//}; +// +// +//class MavlinkStreamAttitudeQuaternion : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamAttitudeQuaternion::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "ATTITUDE_QUATERNION"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_ATTITUDE_QUATERNION; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamAttitudeQuaternion(); +// } +// +//private: +// MavlinkOrbSubscription *att_sub; +// uint64_t att_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamAttitudeQuaternion(MavlinkStreamAttitudeQuaternion &); +// MavlinkStreamAttitudeQuaternion& operator = (const MavlinkStreamAttitudeQuaternion &); +// +//protected: +// explicit MavlinkStreamAttitudeQuaternion() : MavlinkStream(), +// att_sub(nullptr), +// att_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_attitude_s att; +// +// if (att_sub->update(&att_time, &att)) { +// mavlink_msg_attitude_quaternion_send(_channel, +// att.timestamp / 1000, +// att.q[0], +// att.q[1], +// att.q[2], +// att.q[3], +// att.rollspeed, +// att.pitchspeed, +// att.yawspeed); +// } +// } +//}; +// +// +//class MavlinkStreamVFRHUD : public MavlinkStream +//{ +//public: +// +// const char *get_name() const +// { +// return MavlinkStreamVFRHUD::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "VFR_HUD"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_VFR_HUD; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamVFRHUD(); +// } +// +//private: +// MavlinkOrbSubscription *att_sub; +// uint64_t att_time; +// +// MavlinkOrbSubscription *pos_sub; +// uint64_t pos_time; +// +// MavlinkOrbSubscription *armed_sub; +// uint64_t armed_time; +// +// MavlinkOrbSubscription *act_sub; +// uint64_t act_time; +// +// MavlinkOrbSubscription *airspeed_sub; +// uint64_t airspeed_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &); +// MavlinkStreamVFRHUD& operator = (const MavlinkStreamVFRHUD &); +// +//protected: +// explicit MavlinkStreamVFRHUD() : MavlinkStream(), +// att_sub(nullptr), +// att_time(0), +// pos_sub(nullptr), +// pos_time(0), +// armed_sub(nullptr), +// armed_time(0), +// act_sub(nullptr), +// act_time(0), +// airspeed_sub(nullptr), +// airspeed_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); +// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); +// armed_sub = mavlink->add_orb_subscription(ORB_ID(actuator_armed)); +// act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_controls_0)); +// airspeed_sub = mavlink->add_orb_subscription(ORB_ID(airspeed)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_attitude_s att; +// struct vehicle_global_position_s pos; +// struct actuator_armed_s armed; +// struct actuator_controls_s act; +// struct airspeed_s airspeed; +// +// bool updated = att_sub->update(&att_time, &att); +// updated |= pos_sub->update(&pos_time, &pos); +// updated |= armed_sub->update(&armed_time, &armed); +// updated |= act_sub->update(&act_time, &act); +// updated |= airspeed_sub->update(&airspeed_time, &airspeed); +// +// if (updated) { +// float groundspeed = sqrtf(pos.vel_n * pos.vel_n + pos.vel_e * pos.vel_e); +// uint16_t heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F; +// float throttle = armed.armed ? act.control[3] * 100.0f : 0.0f; +// +// mavlink_msg_vfr_hud_send(_channel, +// airspeed.true_airspeed_m_s, +// groundspeed, +// heading, +// throttle, +// pos.alt, +// -pos.vel_d); +// } +// } +//}; +// +// +//class MavlinkStreamGPSRawInt : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamGPSRawInt::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "GPS_RAW_INT"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_GPS_RAW_INT; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamGPSRawInt(); +// } +// +//private: +// MavlinkOrbSubscription *gps_sub; +// uint64_t gps_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamGPSRawInt(MavlinkStreamGPSRawInt &); +// MavlinkStreamGPSRawInt& operator = (const MavlinkStreamGPSRawInt &); +// +//protected: +// explicit MavlinkStreamGPSRawInt() : MavlinkStream(), +// gps_sub(nullptr), +// gps_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// gps_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_gps_position_s gps; +// +// if (gps_sub->update(&gps_time, &gps)) { +// mavlink_msg_gps_raw_int_send(_channel, +// gps.timestamp_position, +// gps.fix_type, +// gps.lat, +// gps.lon, +// gps.alt, +// cm_uint16_from_m_float(gps.eph), +// cm_uint16_from_m_float(gps.epv), +// gps.vel_m_s * 100.0f, +// _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f, +// gps.satellites_used); +// } +// } +//}; +// +// +//class MavlinkStreamGlobalPositionInt : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamGlobalPositionInt::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "GLOBAL_POSITION_INT"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_GLOBAL_POSITION_INT; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamGlobalPositionInt(); +// } +// +//private: +// MavlinkOrbSubscription *pos_sub; +// uint64_t pos_time; +// +// MavlinkOrbSubscription *home_sub; +// uint64_t home_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamGlobalPositionInt(MavlinkStreamGlobalPositionInt &); +// MavlinkStreamGlobalPositionInt& operator = (const MavlinkStreamGlobalPositionInt &); +// +//protected: +// explicit MavlinkStreamGlobalPositionInt() : MavlinkStream(), +// pos_sub(nullptr), +// pos_time(0), +// home_sub(nullptr), +// home_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); +// home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_global_position_s pos; +// struct home_position_s home; +// +// bool updated = pos_sub->update(&pos_time, &pos); +// updated |= home_sub->update(&home_time, &home); +// +// if (updated) { +// mavlink_msg_global_position_int_send(_channel, +// pos.timestamp / 1000, +// pos.lat * 1e7, +// pos.lon * 1e7, +// pos.alt * 1000.0f, +// (pos.alt - home.alt) * 1000.0f, +// pos.vel_n * 100.0f, +// pos.vel_e * 100.0f, +// pos.vel_d * 100.0f, +// _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f); +// } +// } +//}; +// +// +//class MavlinkStreamLocalPositionNED : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamLocalPositionNED::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "LOCAL_POSITION_NED"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_LOCAL_POSITION_NED; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamLocalPositionNED(); +// } +// +//private: +// MavlinkOrbSubscription *pos_sub; +// uint64_t pos_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamLocalPositionNED(MavlinkStreamLocalPositionNED &); +// MavlinkStreamLocalPositionNED& operator = (const MavlinkStreamLocalPositionNED &); +// +//protected: +// explicit MavlinkStreamLocalPositionNED() : MavlinkStream(), +// pos_sub(nullptr), +// pos_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_local_position_s pos; +// +// if (pos_sub->update(&pos_time, &pos)) { +// mavlink_msg_local_position_ned_send(_channel, +// pos.timestamp / 1000, +// pos.x, +// pos.y, +// pos.z, +// pos.vx, +// pos.vy, +// pos.vz); +// } +// } +//}; +// +// +// +//class MavlinkStreamViconPositionEstimate : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamViconPositionEstimate::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "VICON_POSITION_ESTIMATE"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamViconPositionEstimate(); +// } +// +//private: +// MavlinkOrbSubscription *pos_sub; +// uint64_t pos_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamViconPositionEstimate(MavlinkStreamViconPositionEstimate &); +// MavlinkStreamViconPositionEstimate& operator = (const MavlinkStreamViconPositionEstimate &); +// +//protected: +// explicit MavlinkStreamViconPositionEstimate() : MavlinkStream(), +// pos_sub(nullptr), +// pos_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_vicon_position_s pos; +// +// if (pos_sub->update(&pos_time, &pos)) { +// mavlink_msg_vicon_position_estimate_send(_channel, +// pos.timestamp / 1000, +// pos.x, +// pos.y, +// pos.z, +// pos.roll, +// pos.pitch, +// pos.yaw); +// } +// } +//}; +// +// +//class MavlinkStreamGPSGlobalOrigin : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamGPSGlobalOrigin::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "GPS_GLOBAL_ORIGIN"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamGPSGlobalOrigin(); +// } +// +//private: +// MavlinkOrbSubscription *home_sub; +// +// /* do not allow top copying this class */ +// MavlinkStreamGPSGlobalOrigin(MavlinkStreamGPSGlobalOrigin &); +// MavlinkStreamGPSGlobalOrigin& operator = (const MavlinkStreamGPSGlobalOrigin &); +// +//protected: +// explicit MavlinkStreamGPSGlobalOrigin() : MavlinkStream(), +// home_sub(nullptr) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); +// } +// +// void send(const hrt_abstime t) +// { +// /* we're sending the GPS home periodically to ensure the +// * the GCS does pick it up at one point */ +// if (home_sub->is_published()) { +// struct home_position_s home; +// +// if (home_sub->update(&home)) { +// mavlink_msg_gps_global_origin_send(_channel, +// (int32_t)(home.lat * 1e7), +// (int32_t)(home.lon * 1e7), +// (int32_t)(home.alt) * 1000.0f); +// } +// } +// } +//}; +// +//template +//class MavlinkStreamServoOutputRaw : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamServoOutputRaw::get_name_static(); +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; +// } +// +// static const char *get_name_static() +// { +// switch (N) { +// case 0: +// return "SERVO_OUTPUT_RAW_0"; +// +// case 1: +// return "SERVO_OUTPUT_RAW_1"; +// +// case 2: +// return "SERVO_OUTPUT_RAW_2"; +// +// case 3: +// return "SERVO_OUTPUT_RAW_3"; +// } +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamServoOutputRaw(); +// } +// +//private: +// MavlinkOrbSubscription *act_sub; +// uint64_t act_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamServoOutputRaw(MavlinkStreamServoOutputRaw &); +// MavlinkStreamServoOutputRaw& operator = (const MavlinkStreamServoOutputRaw &); +// +//protected: +// explicit MavlinkStreamServoOutputRaw() : MavlinkStream(), +// act_sub(nullptr), +// act_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// orb_id_t act_topics[] = { +// ORB_ID(actuator_outputs_0), +// ORB_ID(actuator_outputs_1), +// ORB_ID(actuator_outputs_2), +// ORB_ID(actuator_outputs_3) +// }; +// +// act_sub = mavlink->add_orb_subscription(act_topics[N]); +// } +// +// void send(const hrt_abstime t) +// { +// struct actuator_outputs_s act; +// +// if (act_sub->update(&act_time, &act)) { +// mavlink_msg_servo_output_raw_send(_channel, +// act.timestamp / 1000, +// N, +// act.output[0], +// act.output[1], +// act.output[2], +// act.output[3], +// act.output[4], +// act.output[5], +// act.output[6], +// act.output[7]); +// } +// } +//}; +// +// +//class MavlinkStreamHILControls : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamHILControls::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "HIL_CONTROLS"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_HIL_CONTROLS; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamHILControls(); +// } +// +//private: +// MavlinkOrbSubscription *status_sub; +// uint64_t status_time; +// +// MavlinkOrbSubscription *pos_sp_triplet_sub; +// uint64_t pos_sp_triplet_time; +// +// MavlinkOrbSubscription *act_sub; +// uint64_t act_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamHILControls(MavlinkStreamHILControls &); +// MavlinkStreamHILControls& operator = (const MavlinkStreamHILControls &); +// +//protected: +// explicit MavlinkStreamHILControls() : MavlinkStream(), +// status_sub(nullptr), +// status_time(0), +// pos_sp_triplet_sub(nullptr), +// pos_sp_triplet_time(0), +// act_sub(nullptr), +// act_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); +// pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); +// act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_status_s status; +// struct position_setpoint_triplet_s pos_sp_triplet; +// struct actuator_outputs_s act; +// +// bool updated = act_sub->update(&act_time, &act); +// updated |= pos_sp_triplet_sub->update(&pos_sp_triplet_time, &pos_sp_triplet); +// updated |= status_sub->update(&status_time, &status); +// +// if (updated && (status.arming_state == ARMING_STATE_ARMED)) { +// /* translate the current syste state to mavlink state and mode */ +// uint8_t mavlink_state; +// uint8_t mavlink_base_mode; +// uint32_t mavlink_custom_mode; +// get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode); +// +// float out[8]; +// +// const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2; +// +// /* scale outputs depending on system type */ +// if (mavlink_system.type == MAV_TYPE_QUADROTOR || +// mavlink_system.type == MAV_TYPE_HEXAROTOR || +// mavlink_system.type == MAV_TYPE_OCTOROTOR) { +// /* multirotors: set number of rotor outputs depending on type */ +// +// unsigned n; +// +// switch (mavlink_system.type) { +// case MAV_TYPE_QUADROTOR: +// n = 4; +// break; +// +// case MAV_TYPE_HEXAROTOR: +// n = 6; +// break; +// +// default: +// n = 8; +// break; +// } +// +// for (unsigned i = 0; i < 8; i++) { +// if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) { +// if (i < n) { +// /* scale PWM out 900..2100 us to 0..1 for rotors */ +// out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); +// +// } else { +// /* scale PWM out 900..2100 us to -1..1 for other channels */ +// out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); +// } +// +// } else { +// /* send 0 when disarmed */ +// out[i] = 0.0f; +// } +// } +// +// } else { +// /* fixed wing: scale throttle to 0..1 and other channels to -1..1 */ +// +// for (unsigned i = 0; i < 8; i++) { +// if (i != 3) { +// /* scale PWM out 900..2100 us to -1..1 for normal channels */ +// out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); +// +// } else { +// /* scale PWM out 900..2100 us to 0..1 for throttle */ +// out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); +// } +// +// } +// } +// +// mavlink_msg_hil_controls_send(_channel, +// hrt_absolute_time(), +// out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7], +// mavlink_base_mode, +// 0); +// } +// } +//}; +// +// +//class MavlinkStreamGlobalPositionSetpointInt : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamGlobalPositionSetpointInt::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "GLOBAL_POSITION_SETPOINT_INT"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamGlobalPositionSetpointInt(); +// } +// +//private: +// MavlinkOrbSubscription *pos_sp_triplet_sub; +// +// /* do not allow top copying this class */ +// MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &); +// MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &); +// +//protected: +// explicit MavlinkStreamGlobalPositionSetpointInt() : MavlinkStream(), +// pos_sp_triplet_sub(nullptr) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); +// } +// +// void send(const hrt_abstime t) +// { +// struct position_setpoint_triplet_s pos_sp_triplet; +// +// if (pos_sp_triplet_sub->update(&pos_sp_triplet)) { +// mavlink_msg_global_position_setpoint_int_send(_channel, +// MAV_FRAME_GLOBAL, +// (int32_t)(pos_sp_triplet.current.lat * 1e7), +// (int32_t)(pos_sp_triplet.current.lon * 1e7), +// (int32_t)(pos_sp_triplet.current.alt * 1000), +// (int16_t)(pos_sp_triplet.current.yaw * M_RAD_TO_DEG_F * 100.0f)); +// } +// } +//}; +// +// +//class MavlinkStreamLocalPositionSetpoint : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamLocalPositionSetpoint::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "LOCAL_POSITION_SETPOINT"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamLocalPositionSetpoint(); +// } +// +//private: +// MavlinkOrbSubscription *pos_sp_sub; +// uint64_t pos_sp_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamLocalPositionSetpoint(MavlinkStreamLocalPositionSetpoint &); +// MavlinkStreamLocalPositionSetpoint& operator = (const MavlinkStreamLocalPositionSetpoint &); +// +//protected: +// explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(), +// pos_sp_sub(nullptr), +// pos_sp_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// pos_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_local_position_setpoint_s pos_sp; +// +// if (pos_sp_sub->update(&pos_sp_time, &pos_sp)) { +// mavlink_msg_local_position_setpoint_send(_channel, +// MAV_FRAME_LOCAL_NED, +// pos_sp.x, +// pos_sp.y, +// pos_sp.z, +// pos_sp.yaw); +// } +// } +//}; +// +// +//class MavlinkStreamRollPitchYawThrustSetpoint : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamRollPitchYawThrustSetpoint::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "ROLL_PITCH_YAW_THRUST_SETPOINT"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamRollPitchYawThrustSetpoint(); +// } +// +//private: +// MavlinkOrbSubscription *att_sp_sub; +// uint64_t att_sp_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &); +// MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &); +// +//protected: +// explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(), +// att_sp_sub(nullptr), +// att_sp_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// att_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_attitude_setpoint_s att_sp; +// +// if (att_sp_sub->update(&att_sp_time, &att_sp)) { +// mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(_channel, +// att_sp.timestamp / 1000, +// att_sp.roll_body, +// att_sp.pitch_body, +// att_sp.yaw_body, +// att_sp.thrust); +// } +// } +//}; +// +// +//class MavlinkStreamRollPitchYawRatesThrustSetpoint : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamRollPitchYawRatesThrustSetpoint(); +// } +// +//private: +// MavlinkOrbSubscription *att_rates_sp_sub; +// uint64_t att_rates_sp_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &); +// MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &); +// +//protected: +// explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(), +// att_rates_sp_sub(nullptr), +// att_rates_sp_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// att_rates_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_rates_setpoint_s att_rates_sp; +// +// if (att_rates_sp_sub->update(&att_rates_sp_time, &att_rates_sp)) { +// mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(_channel, +// att_rates_sp.timestamp / 1000, +// att_rates_sp.roll, +// att_rates_sp.pitch, +// att_rates_sp.yaw, +// att_rates_sp.thrust); +// } +// } +//}; +// +// +//class MavlinkStreamRCChannelsRaw : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamRCChannelsRaw::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "RC_CHANNELS_RAW"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_RC_CHANNELS_RAW; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamRCChannelsRaw(); +// } +// +//private: +// MavlinkOrbSubscription *rc_sub; +// uint64_t rc_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamRCChannelsRaw(MavlinkStreamRCChannelsRaw &); +// MavlinkStreamRCChannelsRaw& operator = (const MavlinkStreamRCChannelsRaw &); +// +//protected: +// explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(), +// rc_sub(nullptr), +// rc_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// rc_sub = mavlink->add_orb_subscription(ORB_ID(input_rc)); +// } +// +// void send(const hrt_abstime t) +// { +// struct rc_input_values rc; +// +// if (rc_sub->update(&rc_time, &rc)) { +// const unsigned port_width = 8; +// +// // Deprecated message (but still needed for compatibility!) +// for (unsigned i = 0; (i * port_width) < rc.channel_count; i++) { +// /* Channels are sent in MAVLink main loop at a fixed interval */ +// mavlink_msg_rc_channels_raw_send(_channel, +// rc.timestamp_publication / 1000, +// i, +// (rc.channel_count > (i * port_width) + 0) ? rc.values[(i * port_width) + 0] : UINT16_MAX, +// (rc.channel_count > (i * port_width) + 1) ? rc.values[(i * port_width) + 1] : UINT16_MAX, +// (rc.channel_count > (i * port_width) + 2) ? rc.values[(i * port_width) + 2] : UINT16_MAX, +// (rc.channel_count > (i * port_width) + 3) ? rc.values[(i * port_width) + 3] : UINT16_MAX, +// (rc.channel_count > (i * port_width) + 4) ? rc.values[(i * port_width) + 4] : UINT16_MAX, +// (rc.channel_count > (i * port_width) + 5) ? rc.values[(i * port_width) + 5] : UINT16_MAX, +// (rc.channel_count > (i * port_width) + 6) ? rc.values[(i * port_width) + 6] : UINT16_MAX, +// (rc.channel_count > (i * port_width) + 7) ? rc.values[(i * port_width) + 7] : UINT16_MAX, +// rc.rssi); +// } +// +// // New message +// mavlink_msg_rc_channels_send(_channel, +// rc.timestamp_publication / 1000, +// rc.channel_count, +// ((rc.channel_count > 0) ? rc.values[0] : UINT16_MAX), +// ((rc.channel_count > 1) ? rc.values[1] : UINT16_MAX), +// ((rc.channel_count > 2) ? rc.values[2] : UINT16_MAX), +// ((rc.channel_count > 3) ? rc.values[3] : UINT16_MAX), +// ((rc.channel_count > 4) ? rc.values[4] : UINT16_MAX), +// ((rc.channel_count > 5) ? rc.values[5] : UINT16_MAX), +// ((rc.channel_count > 6) ? rc.values[6] : UINT16_MAX), +// ((rc.channel_count > 7) ? rc.values[7] : UINT16_MAX), +// ((rc.channel_count > 8) ? rc.values[8] : UINT16_MAX), +// ((rc.channel_count > 9) ? rc.values[9] : UINT16_MAX), +// ((rc.channel_count > 10) ? rc.values[10] : UINT16_MAX), +// ((rc.channel_count > 11) ? rc.values[11] : UINT16_MAX), +// ((rc.channel_count > 12) ? rc.values[12] : UINT16_MAX), +// ((rc.channel_count > 13) ? rc.values[13] : UINT16_MAX), +// ((rc.channel_count > 14) ? rc.values[14] : UINT16_MAX), +// ((rc.channel_count > 15) ? rc.values[15] : UINT16_MAX), +// ((rc.channel_count > 16) ? rc.values[16] : UINT16_MAX), +// ((rc.channel_count > 17) ? rc.values[17] : UINT16_MAX), +// rc.rssi); +// } +// } +//}; +// +// +//class MavlinkStreamManualControl : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamManualControl::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "MANUAL_CONTROL"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_MANUAL_CONTROL; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamManualControl(); +// } +// +//private: +// MavlinkOrbSubscription *manual_sub; +// uint64_t manual_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamManualControl(MavlinkStreamManualControl &); +// MavlinkStreamManualControl& operator = (const MavlinkStreamManualControl &); +// +//protected: +// explicit MavlinkStreamManualControl() : MavlinkStream(), +// manual_sub(nullptr), +// manual_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// manual_sub = mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); +// } +// +// void send(const hrt_abstime t) +// { +// struct manual_control_setpoint_s manual; +// +// if (manual_sub->update(&manual_time, &manual)) { +// mavlink_msg_manual_control_send(_channel, +// mavlink_system.sysid, +// manual.x * 1000, +// manual.y * 1000, +// manual.z * 1000, +// manual.r * 1000, +// 0); +// } +// } +//}; +// +// +//class MavlinkStreamOpticalFlow : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamOpticalFlow::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "OPTICAL_FLOW"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_OPTICAL_FLOW; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamOpticalFlow(); +// } +// +//private: +// MavlinkOrbSubscription *flow_sub; +// uint64_t flow_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamOpticalFlow(MavlinkStreamOpticalFlow &); +// MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &); +// +//protected: +// explicit MavlinkStreamOpticalFlow() : MavlinkStream(), +// flow_sub(nullptr), +// flow_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// flow_sub = mavlink->add_orb_subscription(ORB_ID(optical_flow)); +// } +// +// void send(const hrt_abstime t) +// { +// struct optical_flow_s flow; +// +// if (flow_sub->update(&flow_time, &flow)) { +// mavlink_msg_optical_flow_send(_channel, +// flow.timestamp, +// flow.sensor_id, +// flow.flow_raw_x, flow.flow_raw_y, +// flow.flow_comp_x_m, flow.flow_comp_y_m, +// flow.quality, +// flow.ground_distance_m); +// } +// } +//}; +// +//class MavlinkStreamAttitudeControls : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamAttitudeControls::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "ATTITUDE_CONTROLS"; +// } +// +// uint8_t get_id() +// { +// return 0; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamAttitudeControls(); +// } +// +//private: +// MavlinkOrbSubscription *att_ctrl_sub; +// uint64_t att_ctrl_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamAttitudeControls(MavlinkStreamAttitudeControls &); +// MavlinkStreamAttitudeControls& operator = (const MavlinkStreamAttitudeControls &); +// +//protected: +// explicit MavlinkStreamAttitudeControls() : MavlinkStream(), +// att_ctrl_sub(nullptr), +// att_ctrl_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// att_ctrl_sub = mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); +// } +// +// void send(const hrt_abstime t) +// { +// struct actuator_controls_s att_ctrl; +// +// if (att_ctrl_sub->update(&att_ctrl_time, &att_ctrl)) { +// /* send, add spaces so that string buffer is at least 10 chars long */ +// mavlink_msg_named_value_float_send(_channel, +// att_ctrl.timestamp / 1000, +// "rll ctrl ", +// att_ctrl.control[0]); +// mavlink_msg_named_value_float_send(_channel, +// att_ctrl.timestamp / 1000, +// "ptch ctrl ", +// att_ctrl.control[1]); +// mavlink_msg_named_value_float_send(_channel, +// att_ctrl.timestamp / 1000, +// "yaw ctrl ", +// att_ctrl.control[2]); +// mavlink_msg_named_value_float_send(_channel, +// att_ctrl.timestamp / 1000, +// "thr ctrl ", +// att_ctrl.control[3]); +// } +// } +//}; +// +//class MavlinkStreamNamedValueFloat : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamNamedValueFloat::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "NAMED_VALUE_FLOAT"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamNamedValueFloat(); +// } +// +//private: +// MavlinkOrbSubscription *debug_sub; +// uint64_t debug_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamNamedValueFloat(MavlinkStreamNamedValueFloat &); +// MavlinkStreamNamedValueFloat& operator = (const MavlinkStreamNamedValueFloat &); +// +//protected: +// explicit MavlinkStreamNamedValueFloat() : MavlinkStream(), +// debug_sub(nullptr), +// debug_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// debug_sub = mavlink->add_orb_subscription(ORB_ID(debug_key_value)); +// } +// +// void send(const hrt_abstime t) +// { +// struct debug_key_value_s debug; +// +// if (debug_sub->update(&debug_time, &debug)) { +// /* enforce null termination */ +// debug.key[sizeof(debug.key) - 1] = '\0'; +// +// mavlink_msg_named_value_float_send(_channel, +// debug.timestamp_ms, +// debug.key, +// debug.value); +// } +// } +//}; +// +//class MavlinkStreamCameraCapture : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamCameraCapture::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "CAMERA_CAPTURE"; +// } +// +// uint8_t get_id() +// { +// return 0; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamCameraCapture(); +// } +// +//private: +// MavlinkOrbSubscription *status_sub; +// +// /* do not allow top copying this class */ +// MavlinkStreamCameraCapture(MavlinkStreamCameraCapture &); +// MavlinkStreamCameraCapture& operator = (const MavlinkStreamCameraCapture &); +// +//protected: +// explicit MavlinkStreamCameraCapture() : MavlinkStream(), +// status_sub(nullptr) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); +// } +// +// void send(const hrt_abstime t) +// { +// struct vehicle_status_s status; +// (void)status_sub->update(&status); +// +// if (status.arming_state == ARMING_STATE_ARMED +// || status.arming_state == ARMING_STATE_ARMED_ERROR) { +// +// /* send camera capture on */ +// mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0); +// +// } else { +// /* send camera capture off */ +// mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0); +// } +// } +//}; +// +//class MavlinkStreamDistanceSensor : public MavlinkStream +//{ +//public: +// const char *get_name() const +// { +// return MavlinkStreamDistanceSensor::get_name_static(); +// } +// +// static const char *get_name_static() +// { +// return "DISTANCE_SENSOR"; +// } +// +// uint8_t get_id() +// { +// return MAVLINK_MSG_ID_DISTANCE_SENSOR; +// } +// +// static MavlinkStream *new_instance() +// { +// return new MavlinkStreamDistanceSensor(); +// } +// +//private: +// MavlinkOrbSubscription *range_sub; +// uint64_t range_time; +// +// /* do not allow top copying this class */ +// MavlinkStreamDistanceSensor(MavlinkStreamDistanceSensor &); +// MavlinkStreamDistanceSensor& operator = (const MavlinkStreamDistanceSensor &); +// +//protected: +// explicit MavlinkStreamDistanceSensor() : MavlinkStream(), +// range_sub(nullptr), +// range_time(0) +// {} +// +// void subscribe(Mavlink *mavlink) +// { +// range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder)); +// } +// +// void send(const hrt_abstime t) +// { +// struct range_finder_report range; +// +// if (range_sub->update(&range_time, &range)) { +// +// uint8_t type; +// +// switch (range.type) { +// case RANGE_FINDER_TYPE_LASER: +// type = MAV_DISTANCE_SENSOR_LASER; +// break; +// } +// +// uint8_t id = 0; +// uint8_t orientation = 0; +// uint8_t covariance = 20; +// +// mavlink_msg_distance_sensor_send(_channel, range.timestamp / 1000, type, id, orientation, +// range.minimum_distance*100, range.maximum_distance*100, range.distance*100, covariance); +// } +// } +//}; StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static), new StreamListItem(&MavlinkStreamSysStatus::new_instance, &MavlinkStreamSysStatus::get_name_static), - new StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static), - new StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static), - new StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static), - new StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static), - new StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static), - new StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static), - new StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static), - new StreamListItem(&MavlinkStreamGPSGlobalOrigin::new_instance, &MavlinkStreamGPSGlobalOrigin::get_name_static), - new StreamListItem(&MavlinkStreamServoOutputRaw<0>::new_instance, &MavlinkStreamServoOutputRaw<0>::get_name_static), - new StreamListItem(&MavlinkStreamServoOutputRaw<1>::new_instance, &MavlinkStreamServoOutputRaw<1>::get_name_static), - new StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static), - new StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static), - new StreamListItem(&MavlinkStreamHILControls::new_instance, &MavlinkStreamHILControls::get_name_static), - new StreamListItem(&MavlinkStreamGlobalPositionSetpointInt::new_instance, &MavlinkStreamGlobalPositionSetpointInt::get_name_static), - new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static), - new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static), - new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static), - new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static), - new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static), - new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static), - new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static), - new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static), - new StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static), - new StreamListItem(&MavlinkStreamDistanceSensor::new_instance, &MavlinkStreamDistanceSensor::get_name_static), - new StreamListItem(&MavlinkStreamViconPositionEstimate::new_instance, &MavlinkStreamViconPositionEstimate::get_name_static), +// new StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static), +// new StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static), +// new StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static), +// new StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static), +// new StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static), +// new StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static), +// new StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static), +// new StreamListItem(&MavlinkStreamGPSGlobalOrigin::new_instance, &MavlinkStreamGPSGlobalOrigin::get_name_static), +// new StreamListItem(&MavlinkStreamServoOutputRaw<0>::new_instance, &MavlinkStreamServoOutputRaw<0>::get_name_static), +// new StreamListItem(&MavlinkStreamServoOutputRaw<1>::new_instance, &MavlinkStreamServoOutputRaw<1>::get_name_static), +// new StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static), +// new StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static), +// new StreamListItem(&MavlinkStreamHILControls::new_instance, &MavlinkStreamHILControls::get_name_static), +// new StreamListItem(&MavlinkStreamGlobalPositionSetpointInt::new_instance, &MavlinkStreamGlobalPositionSetpointInt::get_name_static), +// new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static), +// new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static), +// new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static), +// new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static), +// new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static), +// new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static), +// new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static), +// new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static), +// new StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static), +// new StreamListItem(&MavlinkStreamDistanceSensor::new_instance, &MavlinkStreamDistanceSensor::get_name_static), +// new StreamListItem(&MavlinkStreamViconPositionEstimate::new_instance, &MavlinkStreamViconPositionEstimate::get_name_static), nullptr }; diff --git a/src/modules/mavlink/mavlink_messages.h b/src/modules/mavlink/mavlink_messages.h index ee64d0e42..7e4416609 100644 --- a/src/modules/mavlink/mavlink_messages.h +++ b/src/modules/mavlink/mavlink_messages.h @@ -46,10 +46,10 @@ class StreamListItem { public: - MavlinkStream* (*new_instance)(); + MavlinkStream* (*new_instance)(Mavlink *mavlink); const char* (*get_name)(); - StreamListItem(MavlinkStream* (*inst)(), const char* (*name)()) : + StreamListItem(MavlinkStream* (*inst)(Mavlink *mavlink), const char* (*name)()) : new_instance(inst), get_name(name) {}; diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index 068774c47..d17ccc6f9 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -157,15 +157,13 @@ MavlinkMissionManager::update_active_mission(int dataman_id, unsigned count, int void MavlinkMissionManager::send_mission_ack(uint8_t sysid, uint8_t compid, uint8_t type) { - mavlink_message_t msg; mavlink_mission_ack_t wpa; wpa.target_system = sysid; wpa.target_component = compid; wpa.type = type; - mavlink_msg_mission_ack_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpa); - _mavlink->send_message(&msg); + _mavlink->send_message(MAVLINK_MSG_ID_MISSION_ACK, &wpa); if (_verbose) { warnx("WPM: Send MISSION_ACK type %u to ID %u", wpa.type, wpa.target_system); } } @@ -175,13 +173,11 @@ void MavlinkMissionManager::send_mission_current(uint16_t seq) { if (seq < _count) { - mavlink_message_t msg; mavlink_mission_current_t wpc; wpc.seq = seq; - mavlink_msg_mission_current_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpc); - _mavlink->send_message(&msg); + _mavlink->send_message(MAVLINK_MSG_ID_MISSION_CURRENT, &wpc); } else if (seq == 0 && _count == 0) { /* don't broadcast if no WPs */ @@ -199,15 +195,13 @@ MavlinkMissionManager::send_mission_count(uint8_t sysid, uint8_t compid, uint16_ { _time_last_sent = hrt_absolute_time(); - mavlink_message_t msg; mavlink_mission_count_t wpc; wpc.target_system = sysid; wpc.target_component = compid; wpc.count = _count; - mavlink_msg_mission_count_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpc); - _mavlink->send_message(&msg); + _mavlink->send_message(MAVLINK_MSG_ID_MISSION_COUNT, &wpc); if (_verbose) { warnx("WPM: Send MISSION_COUNT %u to ID %u", wpc.count, wpc.target_system); } } @@ -226,13 +220,12 @@ MavlinkMissionManager::send_mission_item(uint8_t sysid, uint8_t compid, uint16_t mavlink_mission_item_t wp; format_mavlink_mission_item(&mission_item, &wp); - mavlink_message_t msg; wp.target_system = sysid; wp.target_component = compid; wp.seq = seq; wp.current = (_current_seq == seq) ? 1 : 0; - mavlink_msg_mission_item_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wp); - _mavlink->send_message(&msg); + + _mavlink->send_message(MAVLINK_MSG_ID_MISSION_ITEM, &wp); if (_verbose) { warnx("WPM: Send MISSION_ITEM seq %u to ID %u", wp.seq, wp.target_system); } @@ -251,13 +244,12 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1 if (seq < _max_count) { _time_last_sent = hrt_absolute_time(); - mavlink_message_t msg; mavlink_mission_request_t wpr; wpr.target_system = sysid; wpr.target_component = compid; wpr.seq = seq; - mavlink_msg_mission_request_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wpr); - _mavlink->send_message(&msg); + + _mavlink->send_message(MAVLINK_MSG_ID_MISSION_REQUEST, &wpr); if (_verbose) { warnx("WPM: Send MISSION_REQUEST seq %u to ID %u", wpr.seq, wpr.target_system); } @@ -272,13 +264,11 @@ MavlinkMissionManager::send_mission_request(uint8_t sysid, uint8_t compid, uint1 void MavlinkMissionManager::send_mission_item_reached(uint16_t seq) { - mavlink_message_t msg; mavlink_mission_item_reached_t wp_reached; wp_reached.seq = seq; - mavlink_msg_mission_item_reached_encode_chan(mavlink_system.sysid, _comp_id, _channel, &msg, &wp_reached); - _mavlink->send_message(&msg); + _mavlink->send_message(MAVLINK_MSG_ID_MISSION_ITEM_REACHED, &wp_reached); if (_verbose) { warnx("WPM: Send MISSION_ITEM_REACHED reached_seq %u", wp_reached.seq); } } diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index b1dae918c..4e8cd4ba4 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -38,11 +38,11 @@ * @author Anton Babushkin */ -//#include +#include #include "mavlink_parameters.h" +#include "mavlink_main.h" -explicit MavlinkParametersManager::MavlinkParametersManager(Mavlink *mavlink) : MavlinkStream(mavlink), _send_all_index(-1) { @@ -51,7 +51,7 @@ MavlinkParametersManager::MavlinkParametersManager(Mavlink *mavlink) : MavlinkSt unsigned MavlinkParametersManager::get_size() { - if (_send_all_index() >= 0) { + if (_send_all_index >= 0) { return MAVLINK_MSG_ID_PARAM_VALUE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; } else { diff --git a/src/modules/mavlink/mavlink_parameters.h b/src/modules/mavlink/mavlink_parameters.h index 9b7a04a73..2a5a205e9 100644 --- a/src/modules/mavlink/mavlink_parameters.h +++ b/src/modules/mavlink/mavlink_parameters.h @@ -40,6 +40,9 @@ #pragma once +#include + +#include "mavlink_bridge_header.h" #include "mavlink_stream.h" class MavlinkParametersManager : public MavlinkStream diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk index 1986ae3c8..08faf102a 100644 --- a/src/modules/mavlink/module.mk +++ b/src/modules/mavlink/module.mk @@ -40,6 +40,7 @@ SRCS += mavlink_main.cpp \ mavlink.c \ mavlink_receiver.cpp \ mavlink_mission.cpp \ + mavlink_parameters.cpp \ mavlink_orb_subscription.cpp \ mavlink_messages.cpp \ mavlink_stream.cpp \ -- cgit v1.2.3 From d70b21c51aacae1a3dae755dca4ba9c3fa7a0d88 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 23 Jul 2014 15:37:56 +0200 Subject: mavlink: move commands stream to mavlink_messages.cpp, bugs fixed --- src/modules/mavlink/mavlink_bridge_header.h | 2 +- src/modules/mavlink/mavlink_commands.cpp | 73 ----------------------------- src/modules/mavlink/mavlink_commands.h | 65 ------------------------- src/modules/mavlink/mavlink_main.cpp | 14 +++--- src/modules/mavlink/mavlink_messages.cpp | 70 +++++++++++++++++++++++++++ src/modules/mavlink/mavlink_parameters.cpp | 2 +- src/modules/mavlink/module.mk | 1 - 7 files changed, 78 insertions(+), 149 deletions(-) delete mode 100644 src/modules/mavlink/mavlink_commands.cpp delete mode 100644 src/modules/mavlink/mavlink_commands.h diff --git a/src/modules/mavlink/mavlink_bridge_header.h b/src/modules/mavlink/mavlink_bridge_header.h index 374d1511c..d82c2dae7 100644 --- a/src/modules/mavlink/mavlink_bridge_header.h +++ b/src/modules/mavlink/mavlink_bridge_header.h @@ -44,7 +44,7 @@ __BEGIN_DECLS -#define MAVLINK_USE_CONVENIENCE_FUNCTIONS +//#define MAVLINK_USE_CONVENIENCE_FUNCTIONS /* use efficient approach, see mavlink_helpers.h */ #define MAVLINK_SEND_UART_BYTES mavlink_send_uart_bytes diff --git a/src/modules/mavlink/mavlink_commands.cpp b/src/modules/mavlink/mavlink_commands.cpp deleted file mode 100644 index b502c3c86..000000000 --- a/src/modules/mavlink/mavlink_commands.cpp +++ /dev/null @@ -1,73 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mavlink_commands.cpp - * Mavlink commands stream implementation. - * - * @author Anton Babushkin - */ - -#include "mavlink_commands.h" - -MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : - _cmd_sub(mavlink->add_orb_subscription(ORB_ID(vehicle_command))), - _cmd{}, - _channel(channel), - _cmd_time(0) -{ -} - -void -MavlinkCommandsStream::update(const hrt_abstime t) -{ - struct vehicle_command_s cmd; - - if (_cmd_sub->update(&_cmd_time, &cmd)) { - /* only send commands for other systems/components */ - if (cmd.target_system != mavlink_system.sysid || cmd.target_component != mavlink_system.compid) { - mavlink_msg_command_long_send(_channel, - cmd.target_system, - cmd.target_component, - cmd.command, - cmd.confirmation, - cmd.param1, - cmd.param2, - cmd.param3, - cmd.param4, - cmd.param5, - cmd.param6, - cmd.param7); - } - } -} diff --git a/src/modules/mavlink/mavlink_commands.h b/src/modules/mavlink/mavlink_commands.h deleted file mode 100644 index abdba34b9..000000000 --- a/src/modules/mavlink/mavlink_commands.h +++ /dev/null @@ -1,65 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2014 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mavlink_commands.h - * Mavlink commands stream definition. - * - * @author Anton Babushkin - */ - -#ifndef MAVLINK_COMMANDS_H_ -#define MAVLINK_COMMANDS_H_ - -#include -#include - -class Mavlink; -class MavlinkCommansStream; - -#include "mavlink_main.h" - -class MavlinkCommandsStream -{ -private: - MavlinkOrbSubscription *_cmd_sub; - struct vehicle_command_s *_cmd; - mavlink_channel_t _channel; - uint64_t _cmd_time; - -public: - MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel); - void update(const hrt_abstime t); -}; - -#endif /* MAVLINK_COMMANDS_H_ */ diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index dca76c950..4f4bf8691 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -78,7 +78,6 @@ #include "mavlink_messages.h" #include "mavlink_receiver.h" #include "mavlink_rate_limiter.h" -#include "mavlink_commands.h" #ifndef MAVLINK_CRC_EXTRA #error MAVLINK_CRC_EXTRA has to be defined on PX4 systems @@ -840,7 +839,7 @@ Mavlink::send_statustext(unsigned severity, const char *string) break; } - mavlink_msg_statustext_send(_channel, statustext.severity, statustext.text); + send_message(MAVLINK_MSG_ID_STATUSTEXT, &statustext); return OK; } else { @@ -1313,13 +1312,14 @@ Mavlink::task_main(int argc, char *argv[]) struct vehicle_status_s status; status_sub->update(&status_time, &status); - MavlinkCommandsStream commands_stream(this, _channel); - /* add default streams depending on mode */ /* HEARTBEAT is constant rate stream, rate never adjusted */ configure_stream("HEARTBEAT", 1.0f); + /* COMMAND_LONG stream: use high rate to avoid commands skipping */ + configure_stream("COMMAND_LONG", 100.0f); + /* PARAM_VALUE stream */ _parameters_manager = (MavlinkParametersManager *) MavlinkParametersManager::new_instance(this); _parameters_manager->set_interval(interval_from_rate(30.0f)); @@ -1384,9 +1384,6 @@ Mavlink::task_main(int argc, char *argv[]) set_hil_enabled(status.hil_state == HIL_STATE_ON); } - /* update commands stream */ - commands_stream.update(t); - /* check for requested subscriptions */ if (_subscribe_to_stream != nullptr) { if (OK == configure_stream(_subscribe_to_stream, _subscribe_to_stream_rate)) { @@ -1469,7 +1466,8 @@ Mavlink::task_main(int argc, char *argv[]) pthread_mutex_unlock(&_message_buffer_mutex); - _mavlink_resend_uart(_channel, &msg); + // TODO implement message resending + //_mavlink_resend_uart(_channel, &msg); } } diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 7dc3ebac1..a8b4d11cc 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -312,6 +312,75 @@ protected: } }; +class MavlinkStreamCommandLong : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamCommandLong::get_name_static(); + } + + static const char *get_name_static() + { + return "COMMAND_LONG"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_COMMAND_LONG; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamCommandLong(mavlink); + } + + unsigned get_size() { return 0; } // commands stream is not regular and not predictable + +private: + MavlinkOrbSubscription *_cmd_sub; + uint64_t _cmd_time; + + /* do not allow top copying this class */ + MavlinkStreamCommandLong(MavlinkStreamCommandLong &); + MavlinkStreamCommandLong& operator = (const MavlinkStreamCommandLong &); + +protected: + explicit MavlinkStreamCommandLong(Mavlink *mavlink) : MavlinkStream(mavlink), + _cmd_sub(nullptr), + _cmd_time(0) + {} + + void subscribe() { + _cmd_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); + } + + void send(const hrt_abstime t) + { + struct vehicle_command_s cmd; + + if (_cmd_sub->update(&_cmd_time, &cmd)) { + /* only send commands for other systems/components */ + if (cmd.target_system != mavlink_system.sysid || cmd.target_component != mavlink_system.compid) { + mavlink_command_long_t mavcmd; + + mavcmd.target_system = cmd.target_system; + mavcmd.target_component = cmd.target_component; + mavcmd.command = cmd.command; + mavcmd.confirmation = cmd.confirmation; + mavcmd.param1 = cmd.param1; + mavcmd.param2 = cmd.param2; + mavcmd.param3 = cmd.param3; + mavcmd.param4 = cmd.param4; + mavcmd.param5 = cmd.param5; + mavcmd.param6 = cmd.param6; + mavcmd.param7 = cmd.param7; + + _mavlink->send_message(MAVLINK_MSG_ID_COMMAND_LONG, &mavcmd); + } + } + } +}; class MavlinkStreamSysStatus : public MavlinkStream { @@ -1926,6 +1995,7 @@ protected: StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static), + new StreamListItem(&MavlinkStreamCommandLong::new_instance, &MavlinkStreamCommandLong::get_name_static), new StreamListItem(&MavlinkStreamSysStatus::new_instance, &MavlinkStreamSysStatus::get_name_static), // new StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static), // new StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static), diff --git a/src/modules/mavlink/mavlink_parameters.cpp b/src/modules/mavlink/mavlink_parameters.cpp index 4e8cd4ba4..cd5f53d88 100644 --- a/src/modules/mavlink/mavlink_parameters.cpp +++ b/src/modules/mavlink/mavlink_parameters.cpp @@ -147,7 +147,7 @@ MavlinkParametersManager::send(const hrt_abstime t) if (_send_all_index >= 0) { send_param(param_for_index(_send_all_index)); _send_all_index++; - if (_send_all_index >= param_count()) { + if (_send_all_index >= (int) param_count()) { _send_all_index = -1; } } diff --git a/src/modules/mavlink/module.mk b/src/modules/mavlink/module.mk index 08faf102a..91fdd6154 100644 --- a/src/modules/mavlink/module.mk +++ b/src/modules/mavlink/module.mk @@ -45,7 +45,6 @@ SRCS += mavlink_main.cpp \ mavlink_messages.cpp \ mavlink_stream.cpp \ mavlink_rate_limiter.cpp \ - mavlink_commands.cpp \ mavlink_ftp.cpp INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink -- cgit v1.2.3 From 1fdc666bb0be393f048c85b1827494beedff0426 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 23 Jul 2014 16:53:19 +0200 Subject: Update NuttX to deal with parity --- NuttX | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/NuttX b/NuttX index 7e1b97bcf..088146b90 160000 --- a/NuttX +++ b/NuttX @@ -1 +1 @@ -Subproject commit 7e1b97bcf10d8495169eec355988ca5890bfd5df +Subproject commit 088146b90eee5b614ea6386a64dae343a49a5172 -- cgit v1.2.3 From f7a40c5c6dcccf0ad14e97ef7fe1e426230e6e01 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 23 Jul 2014 16:55:42 +0200 Subject: Improve I2C address comment. Make filter much stronger to damp any non-realistic vehicle motion. --- src/drivers/meas_airspeed/meas_airspeed.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 6ab437716..118c35960 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -92,7 +92,7 @@ #include /* I2C bus address is 1010001x */ -#define I2C_ADDRESS_MS4525DO 0x28 //0x51 /* 7-bit address. */ +#define I2C_ADDRESS_MS4525DO 0x28 /**< 7-bit address. Depends on the order code (this is for code "I") */ #define PATH_MS4525 "/dev/ms4525" /* The MS5525DSO address is 111011Cx, where C is the complementary value of the pin CSB */ #define I2C_ADDRESS_MS5525DSO 0x77 //0x77/* 7-bit address, addr. pin pulled low */ @@ -102,9 +102,9 @@ #define ADDR_READ_MR 0x00 /* write to this address to start conversion */ /* Measurement rate is 100Hz */ -#define MEAS_RATE 100.0f -#define MEAS_DRIVER_FILTER_FREQ 3.0f -#define CONVERSION_INTERVAL (1000000 / 100) /* microseconds */ +#define MEAS_RATE 100 +#define MEAS_DRIVER_FILTER_FREQ 0.5f +#define CONVERSION_INTERVAL (1000000 / MEAS_RATE) /* microseconds */ class MEASAirspeed : public Airspeed { -- cgit v1.2.3 From 2313bf7cd5cbf14ffaec61116cce84b9c0c18653 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 23 Jul 2014 16:59:04 +0200 Subject: mTECS: Note better filter defaults to get airspeed response a bit smoother. Damp also ACC response with filter more than currently --- src/modules/fw_pos_control_l1/mtecs/mTecs_params.c | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c index 4ca31fe20..7cfe63fbc 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c @@ -241,7 +241,14 @@ PARAM_DEFINE_FLOAT(MT_FPA_MAX, 30.0f); * * @group mTECS */ -PARAM_DEFINE_FLOAT(MT_A_LP, 1.0f); +PARAM_DEFINE_FLOAT(MT_A_LP, 0.5f); + +/** + * Airspeed derivative calculation lowpass + * + * @group mTECS + */ +PARAM_DEFINE_FLOAT(MT_AD_LP, 0.5f); /** * P gain for the airspeed control @@ -268,7 +275,7 @@ PARAM_DEFINE_FLOAT(MT_ACC_D, 0.0f); * * @group mTECS */ -PARAM_DEFINE_FLOAT(MT_ACC_D_LP, 1.0f); +PARAM_DEFINE_FLOAT(MT_ACC_D_LP, 0.5f); /** * Minimal acceleration (air) @@ -286,13 +293,6 @@ PARAM_DEFINE_FLOAT(MT_ACC_MIN, -40.0f); */ PARAM_DEFINE_FLOAT(MT_ACC_MAX, 40.0f); -/** - * Airspeed derivative calculation lowpass - * - * @group mTECS - */ -PARAM_DEFINE_FLOAT(MT_AD_LP, 1.0f); - /** * Minimal throttle during takeoff * -- cgit v1.2.3 From 7ecf66c06d15fb9a8c04f96b5bd05fe1c93138fe Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 23 Jul 2014 17:36:10 +0200 Subject: mavlink: bugs fixed --- src/modules/mavlink/mavlink_main.cpp | 22 ++++++++++------------ src/modules/mavlink/mavlink_messages.cpp | 4 ++-- src/modules/mavlink/mavlink_stream.cpp | 13 +++++++++++-- 3 files changed, 23 insertions(+), 16 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 4f4bf8691..f3246c380 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -146,7 +146,7 @@ Mavlink::Mavlink() : _baudrate(57600), _datarate(1000), _datarate_events(500), - _rate_mult(0.0f), + _rate_mult(1.0f), _mavlink_param_queue_index(0), mavlink_link_termination_allowed(false), _subscribe_to_stream(nullptr), @@ -724,7 +724,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) _last_write_try_time = hrt_absolute_time(); /* check if there is space in the buffer, let it overflow else */ - if (buf_free >= TX_BUFFER_GAP) { + if (buf_free < TX_BUFFER_GAP) { warnx("SKIP msgid %i, %i bytes", msgid, packet_len); /* no enough space in buffer to send */ count_txerr(); @@ -749,9 +749,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) uint16_t checksum; crc_init(&checksum); crc_accumulate_buffer(&checksum, (const char*) &buf[1], MAVLINK_CORE_HEADER_LEN + payload_len); -#if MAVLINK_CRC_EXTRA crc_accumulate(mavlink_message_crcs[msgid], &checksum); -#endif buf[MAVLINK_NUM_HEADER_BYTES + payload_len] = (uint8_t)(checksum & 0xFF); buf[MAVLINK_NUM_HEADER_BYTES + payload_len + 1] = (uint8_t)(checksum >> 8); @@ -1127,7 +1125,7 @@ Mavlink::update_rate_mult() } } - _rate_mult = ((float)_datarate - const_rate) / (rate - const_rate); + _rate_mult = ((float)_datarate - const_rate) / rate; } int @@ -1250,8 +1248,6 @@ Mavlink::task_main(int argc, char *argv[]) break; } - update_rate_mult(); - warnx("data rate: %d Bytes/s, port: %s, baud: %d", _datarate, _device_name, _baudrate); /* flush stdout in case MAVLink is about to take it over */ @@ -1328,7 +1324,7 @@ Mavlink::task_main(int argc, char *argv[]) switch (_mode) { case MAVLINK_MODE_NORMAL: configure_stream("SYS_STATUS", 1.0f); - configure_stream("GPS_GLOBAL_ORIGIN", 0.5f); + /*configure_stream("GPS_GLOBAL_ORIGIN", 0.5f); configure_stream("HIGHRES_IMU", 1.0f); configure_stream("ATTITUDE", 10.0f); configure_stream("VFR_HUD", 8.0f); @@ -1340,6 +1336,7 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f); configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f); configure_stream("DISTANCE_SENSOR", 0.5f); + */ break; case MAVLINK_MODE_CAMERA: @@ -1353,9 +1350,6 @@ Mavlink::task_main(int argc, char *argv[]) break; } - /* don't send parameters on startup without request */ - _mavlink_param_queue_index = param_count(); - float base_rate_mult = _datarate / 1000.0f; MavlinkRateLimiter fast_rate_limiter(30000.0f / base_rate_mult); @@ -1374,6 +1368,9 @@ Mavlink::task_main(int argc, char *argv[]) hrt_abstime t = hrt_absolute_time(); + update_rate_mult(); + warnx("rate mult %f", (double)_rate_mult); + if (param_sub->update(¶m_time, nullptr)) { /* parameters updated */ mavlink_update_system(); @@ -1410,7 +1407,8 @@ Mavlink::task_main(int argc, char *argv[]) } if (fast_rate_limiter.check(t)) { - _mission_manager->eventloop(); + // TODO missions + //_mission_manager->eventloop(); if (!mavlink_logbuffer_is_empty(&_logbuffer)) { struct mavlink_logmessage msg; diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index a8b4d11cc..20b1a966f 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -305,7 +305,7 @@ protected: msg.custom_mode = 0; get_mavlink_mode_state(&status, &pos_sp_triplet, &msg.system_status, &msg.base_mode, &msg.custom_mode); msg.type = mavlink_system.type; - msg.autopilot = mavlink_system.type; + msg.autopilot = MAV_AUTOPILOT_PX4; msg.mavlink_version = 3; _mavlink->send_message(MAVLINK_MSG_ID_HEARTBEAT, &msg); @@ -352,7 +352,7 @@ protected: {} void subscribe() { - _cmd_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); + _cmd_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_command)); } void send(const hrt_abstime t) diff --git a/src/modules/mavlink/mavlink_stream.cpp b/src/modules/mavlink/mavlink_stream.cpp index da3a55172..5b9e45d3e 100644 --- a/src/modules/mavlink/mavlink_stream.cpp +++ b/src/modules/mavlink/mavlink_stream.cpp @@ -71,12 +71,21 @@ int MavlinkStream::update(const hrt_abstime t) { uint64_t dt = t - _last_sent; - unsigned int interval = _interval * _mavlink->get_rate_mult(); + unsigned int interval = _interval; + + if (!const_rate()) { + interval /= _mavlink->get_rate_mult(); + } if (dt > 0 && dt >= interval) { /* interval expired, send message */ send(t); - _last_sent = t; + if (const_rate()) { + _last_sent = (t / _interval) * _interval; + + } else { + _last_sent = t; + } return 0; } -- cgit v1.2.3 From 20698c751c62ca6f11aa910b3c3f180fe30211ff Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 23 Jul 2014 22:40:55 +0200 Subject: mavlink: HIGHRES_IMU stream added --- src/modules/mavlink/mavlink_main.cpp | 5 +- src/modules/mavlink/mavlink_messages.cpp | 246 ++++++++++++++++--------------- 2 files changed, 133 insertions(+), 118 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index f3246c380..e49e99a9b 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1324,7 +1324,7 @@ Mavlink::task_main(int argc, char *argv[]) switch (_mode) { case MAVLINK_MODE_NORMAL: configure_stream("SYS_STATUS", 1.0f); - /*configure_stream("GPS_GLOBAL_ORIGIN", 0.5f); + configure_stream("GPS_GLOBAL_ORIGIN", 0.5f); configure_stream("HIGHRES_IMU", 1.0f); configure_stream("ATTITUDE", 10.0f); configure_stream("VFR_HUD", 8.0f); @@ -1336,7 +1336,6 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f); configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f); configure_stream("DISTANCE_SENSOR", 0.5f); - */ break; case MAVLINK_MODE_CAMERA: @@ -1369,7 +1368,7 @@ Mavlink::task_main(int argc, char *argv[]) hrt_abstime t = hrt_absolute_time(); update_rate_mult(); - warnx("rate mult %f", (double)_rate_mult); + warnx("rate mult %.2f", (double)_rate_mult); if (param_sub->update(¶m_time, nullptr)) { /* parameters updated */ diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 20b1a966f..a77d34c71 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -454,99 +454,115 @@ protected: }; -//class MavlinkStreamHighresIMU : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamHighresIMU::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "HIGHRES_IMU"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_HIGHRES_IMU; -// } -// -// static MavlinkStream *new_instance() -// { -// return new MavlinkStreamHighresIMU(); -// } -// -//private: -// MavlinkOrbSubscription *sensor_sub; -// uint64_t sensor_time; -// -// uint64_t accel_timestamp; -// uint64_t gyro_timestamp; -// uint64_t mag_timestamp; -// uint64_t baro_timestamp; -// -// /* do not allow top copying this class */ -// MavlinkStreamHighresIMU(MavlinkStreamHighresIMU &); -// MavlinkStreamHighresIMU& operator = (const MavlinkStreamHighresIMU &); -// -//protected: -// explicit MavlinkStreamHighresIMU() : MavlinkStream(), -// sensor_sub(nullptr), -// sensor_time(0), -// accel_timestamp(0), -// gyro_timestamp(0), -// mag_timestamp(0), -// baro_timestamp(0) -// {} -// -// void subscribe(Mavlink *mavlink) -// { -// sensor_sub = mavlink->add_orb_subscription(ORB_ID(sensor_combined)); -// } -// -// void send(const hrt_abstime t) -// { -// struct sensor_combined_s sensor; -// -// if (sensor_sub->update(&sensor_time, &sensor)) { -// uint16_t fields_updated = 0; -// -// if (accel_timestamp != sensor.accelerometer_timestamp) { -// /* mark first three dimensions as changed */ -// fields_updated |= (1 << 0) | (1 << 1) | (1 << 2); -// accel_timestamp = sensor.accelerometer_timestamp; -// } -// -// if (gyro_timestamp != sensor.timestamp) { -// /* mark second group dimensions as changed */ -// fields_updated |= (1 << 3) | (1 << 4) | (1 << 5); -// gyro_timestamp = sensor.timestamp; -// } -// -// if (mag_timestamp != sensor.magnetometer_timestamp) { -// /* mark third group dimensions as changed */ -// fields_updated |= (1 << 6) | (1 << 7) | (1 << 8); -// mag_timestamp = sensor.magnetometer_timestamp; -// } -// -// if (baro_timestamp != sensor.baro_timestamp) { -// /* mark last group dimensions as changed */ -// fields_updated |= (1 << 9) | (1 << 11) | (1 << 12); -// baro_timestamp = sensor.baro_timestamp; -// } -// -// mavlink_msg_highres_imu_send(_channel, -// sensor.timestamp, -// sensor.accelerometer_m_s2[0], sensor.accelerometer_m_s2[1], sensor.accelerometer_m_s2[2], -// sensor.gyro_rad_s[0], sensor.gyro_rad_s[1], sensor.gyro_rad_s[2], -// sensor.magnetometer_ga[0], sensor.magnetometer_ga[1], sensor.magnetometer_ga[2], -// sensor.baro_pres_mbar, sensor.differential_pressure_pa, -// sensor.baro_alt_meter, sensor.baro_temp_celcius, -// fields_updated); -// } -// } -//}; +class MavlinkStreamHighresIMU : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamHighresIMU::get_name_static(); + } + + static const char *get_name_static() + { + return "HIGHRES_IMU"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_HIGHRES_IMU; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamHighresIMU(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_HIGHRES_IMU_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *sensor_sub; + uint64_t sensor_time; + + uint64_t accel_timestamp; + uint64_t gyro_timestamp; + uint64_t mag_timestamp; + uint64_t baro_timestamp; + + /* do not allow top copying this class */ + MavlinkStreamHighresIMU(MavlinkStreamHighresIMU &); + MavlinkStreamHighresIMU& operator = (const MavlinkStreamHighresIMU &); + +protected: + explicit MavlinkStreamHighresIMU(Mavlink *mavlink) : MavlinkStream(mavlink), + sensor_sub(nullptr), + sensor_time(0), + accel_timestamp(0), + gyro_timestamp(0), + mag_timestamp(0), + baro_timestamp(0) + {} + + void subscribe() + { + sensor_sub = _mavlink->add_orb_subscription(ORB_ID(sensor_combined)); + } + + void send(const hrt_abstime t) + { + struct sensor_combined_s sensor; + + if (sensor_sub->update(&sensor_time, &sensor)) { + uint16_t fields_updated = 0; + + if (accel_timestamp != sensor.accelerometer_timestamp) { + /* mark first three dimensions as changed */ + fields_updated |= (1 << 0) | (1 << 1) | (1 << 2); + accel_timestamp = sensor.accelerometer_timestamp; + } + + if (gyro_timestamp != sensor.timestamp) { + /* mark second group dimensions as changed */ + fields_updated |= (1 << 3) | (1 << 4) | (1 << 5); + gyro_timestamp = sensor.timestamp; + } + + if (mag_timestamp != sensor.magnetometer_timestamp) { + /* mark third group dimensions as changed */ + fields_updated |= (1 << 6) | (1 << 7) | (1 << 8); + mag_timestamp = sensor.magnetometer_timestamp; + } + + if (baro_timestamp != sensor.baro_timestamp) { + /* mark last group dimensions as changed */ + fields_updated |= (1 << 9) | (1 << 11) | (1 << 12); + baro_timestamp = sensor.baro_timestamp; + } + + mavlink_highres_imu_t msg; + + msg.time_usec = sensor.timestamp; + msg.xacc = sensor.accelerometer_m_s2[0]; + msg.yacc = sensor.accelerometer_m_s2[1]; + msg.zacc = sensor.accelerometer_m_s2[2]; + msg.xgyro = sensor.gyro_rad_s[0]; + msg.ygyro = sensor.gyro_rad_s[1]; + msg.zgyro = sensor.gyro_rad_s[2]; + msg.xmag = sensor.magnetometer_ga[0]; + msg.ymag = sensor.magnetometer_ga[1]; + msg.zmag = sensor.magnetometer_ga[2]; + msg.abs_pressure = sensor.baro_pres_mbar; + msg.diff_pressure = sensor.differential_pressure_pa; + msg.pressure_alt = sensor.baro_alt_meter; + msg.temperature = sensor.baro_temp_celcius; + msg.fields_updated = fields_updated; + + _mavlink->send_message(MAVLINK_MSG_ID_HIGHRES_IMU, &msg); + } + } +}; // // //class MavlinkStreamAttitude : public MavlinkStream @@ -567,7 +583,7 @@ protected: // return MAVLINK_MSG_ID_ATTITUDE; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamAttitude(); // } @@ -624,7 +640,7 @@ protected: // return MAVLINK_MSG_ID_ATTITUDE_QUATERNION; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamAttitudeQuaternion(); // } @@ -686,7 +702,7 @@ protected: // return MAVLINK_MSG_ID_VFR_HUD; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamVFRHUD(); // } @@ -783,7 +799,7 @@ protected: // return MAVLINK_MSG_ID_GPS_RAW_INT; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamGPSRawInt(); // } @@ -846,7 +862,7 @@ protected: // return MAVLINK_MSG_ID_GLOBAL_POSITION_INT; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamGlobalPositionInt(); // } @@ -918,7 +934,7 @@ protected: // return MAVLINK_MSG_ID_LOCAL_POSITION_NED; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamLocalPositionNED(); // } @@ -979,7 +995,7 @@ protected: // return MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamViconPositionEstimate(); // } @@ -1039,7 +1055,7 @@ protected: // return MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamGPSGlobalOrigin(); // } @@ -1109,7 +1125,7 @@ protected: // } // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamServoOutputRaw(); // } @@ -1179,7 +1195,7 @@ protected: // return MAVLINK_MSG_ID_HIL_CONTROLS; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamHILControls(); // } @@ -1319,7 +1335,7 @@ protected: // return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamGlobalPositionSetpointInt(); // } @@ -1375,7 +1391,7 @@ protected: // return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamLocalPositionSetpoint(); // } @@ -1433,7 +1449,7 @@ protected: // return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamRollPitchYawThrustSetpoint(); // } @@ -1491,7 +1507,7 @@ protected: // return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamRollPitchYawRatesThrustSetpoint(); // } @@ -1549,7 +1565,7 @@ protected: // return MAVLINK_MSG_ID_RC_CHANNELS_RAW; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamRCChannelsRaw(); // } @@ -1643,7 +1659,7 @@ protected: // return MAVLINK_MSG_ID_MANUAL_CONTROL; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamManualControl(); // } @@ -1702,7 +1718,7 @@ protected: // return MAVLINK_MSG_ID_OPTICAL_FLOW; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamOpticalFlow(); // } @@ -1760,7 +1776,7 @@ protected: // return 0; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamAttitudeControls(); // } @@ -1828,7 +1844,7 @@ protected: // return MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamNamedValueFloat(); // } @@ -1886,7 +1902,7 @@ protected: // return 0; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamCameraCapture(); // } @@ -1944,7 +1960,7 @@ protected: // return MAVLINK_MSG_ID_DISTANCE_SENSOR; // } // -// static MavlinkStream *new_instance() +// static MavlinkStream *new_instance(Mavlink *mavlink) // { // return new MavlinkStreamDistanceSensor(); // } @@ -1997,7 +2013,7 @@ StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static), new StreamListItem(&MavlinkStreamCommandLong::new_instance, &MavlinkStreamCommandLong::get_name_static), new StreamListItem(&MavlinkStreamSysStatus::new_instance, &MavlinkStreamSysStatus::get_name_static), -// new StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static), + new StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static), // new StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static), // new StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static), // new StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static), -- cgit v1.2.3 From a65b7aee0bc07eeb7545f4a3206e860791b64a36 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 23 Jul 2014 22:54:48 +0200 Subject: mavlink: ATTITUDE, ATTITUDE_QUATERNION, VFR_HUD streams added --- src/modules/mavlink/mavlink_messages.cpp | 544 ++++++++++++++++--------------- 1 file changed, 284 insertions(+), 260 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index a77d34c71..575268814 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -563,224 +563,248 @@ protected: } } }; -// -// -//class MavlinkStreamAttitude : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamAttitude::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "ATTITUDE"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_ATTITUDE; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamAttitude(); -// } -// -//private: -// MavlinkOrbSubscription *att_sub; -// uint64_t att_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamAttitude(MavlinkStreamAttitude &); -// MavlinkStreamAttitude& operator = (const MavlinkStreamAttitude &); -// -// -//protected: -// explicit MavlinkStreamAttitude() : MavlinkStream(), -// att_sub(nullptr), -// att_time(0) -// {} -// -// void subscribe(Mavlink *mavlink) -// { -// att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_attitude_s att; -// -// if (att_sub->update(&att_time, &att)) { -// mavlink_msg_attitude_send(_channel, -// att.timestamp / 1000, -// att.roll, att.pitch, att.yaw, -// att.rollspeed, att.pitchspeed, att.yawspeed); -// } -// } -//}; -// -// -//class MavlinkStreamAttitudeQuaternion : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamAttitudeQuaternion::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "ATTITUDE_QUATERNION"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_ATTITUDE_QUATERNION; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamAttitudeQuaternion(); -// } -// -//private: -// MavlinkOrbSubscription *att_sub; -// uint64_t att_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamAttitudeQuaternion(MavlinkStreamAttitudeQuaternion &); -// MavlinkStreamAttitudeQuaternion& operator = (const MavlinkStreamAttitudeQuaternion &); -// -//protected: -// explicit MavlinkStreamAttitudeQuaternion() : MavlinkStream(), -// att_sub(nullptr), -// att_time(0) -// {} -// -// void subscribe(Mavlink *mavlink) -// { -// att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_attitude_s att; -// -// if (att_sub->update(&att_time, &att)) { -// mavlink_msg_attitude_quaternion_send(_channel, -// att.timestamp / 1000, -// att.q[0], -// att.q[1], -// att.q[2], -// att.q[3], -// att.rollspeed, -// att.pitchspeed, -// att.yawspeed); -// } -// } -//}; -// -// -//class MavlinkStreamVFRHUD : public MavlinkStream -//{ -//public: -// -// const char *get_name() const -// { -// return MavlinkStreamVFRHUD::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "VFR_HUD"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_VFR_HUD; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamVFRHUD(); -// } -// -//private: -// MavlinkOrbSubscription *att_sub; -// uint64_t att_time; -// -// MavlinkOrbSubscription *pos_sub; -// uint64_t pos_time; -// -// MavlinkOrbSubscription *armed_sub; -// uint64_t armed_time; -// -// MavlinkOrbSubscription *act_sub; -// uint64_t act_time; -// -// MavlinkOrbSubscription *airspeed_sub; -// uint64_t airspeed_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &); -// MavlinkStreamVFRHUD& operator = (const MavlinkStreamVFRHUD &); -// -//protected: -// explicit MavlinkStreamVFRHUD() : MavlinkStream(), -// att_sub(nullptr), -// att_time(0), -// pos_sub(nullptr), -// pos_time(0), -// armed_sub(nullptr), -// armed_time(0), -// act_sub(nullptr), -// act_time(0), -// airspeed_sub(nullptr), -// airspeed_time(0) -// {} -// -// void subscribe(Mavlink *mavlink) -// { -// att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); -// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); -// armed_sub = mavlink->add_orb_subscription(ORB_ID(actuator_armed)); -// act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_controls_0)); -// airspeed_sub = mavlink->add_orb_subscription(ORB_ID(airspeed)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_attitude_s att; -// struct vehicle_global_position_s pos; -// struct actuator_armed_s armed; -// struct actuator_controls_s act; -// struct airspeed_s airspeed; -// -// bool updated = att_sub->update(&att_time, &att); -// updated |= pos_sub->update(&pos_time, &pos); -// updated |= armed_sub->update(&armed_time, &armed); -// updated |= act_sub->update(&act_time, &act); -// updated |= airspeed_sub->update(&airspeed_time, &airspeed); -// -// if (updated) { -// float groundspeed = sqrtf(pos.vel_n * pos.vel_n + pos.vel_e * pos.vel_e); -// uint16_t heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F; -// float throttle = armed.armed ? act.control[3] * 100.0f : 0.0f; -// -// mavlink_msg_vfr_hud_send(_channel, -// airspeed.true_airspeed_m_s, -// groundspeed, -// heading, -// throttle, -// pos.alt, -// -pos.vel_d); -// } -// } -//}; -// -// + + +class MavlinkStreamAttitude : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamAttitude::get_name_static(); + } + + static const char *get_name_static() + { + return "ATTITUDE"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_ATTITUDE; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamAttitude(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_ATTITUDE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *att_sub; + uint64_t att_time; + + /* do not allow top copying this class */ + MavlinkStreamAttitude(MavlinkStreamAttitude &); + MavlinkStreamAttitude& operator = (const MavlinkStreamAttitude &); + + +protected: + explicit MavlinkStreamAttitude(Mavlink *mavlink) : MavlinkStream(mavlink), + att_sub(nullptr), + att_time(0) + {} + + void subscribe() + { + att_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); + } + + void send(const hrt_abstime t) + { + struct vehicle_attitude_s att; + + if (att_sub->update(&att_time, &att)) { + mavlink_attitude_t msg; + + msg.time_boot_ms = att.timestamp / 1000; + msg.roll = att.roll; + msg.pitch = att.pitch; + msg.yaw = att.yaw; + msg.rollspeed = att.rollspeed; + msg.pitchspeed = att.pitchspeed; + msg.yawspeed = att.yawspeed; + + _mavlink->send_message(MAVLINK_MSG_ID_ATTITUDE, &msg); + } + } +}; + + +class MavlinkStreamAttitudeQuaternion : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamAttitudeQuaternion::get_name_static(); + } + + static const char *get_name_static() + { + return "ATTITUDE_QUATERNION"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_ATTITUDE_QUATERNION; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamAttitudeQuaternion(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *att_sub; + uint64_t att_time; + + /* do not allow top copying this class */ + MavlinkStreamAttitudeQuaternion(MavlinkStreamAttitudeQuaternion &); + MavlinkStreamAttitudeQuaternion& operator = (const MavlinkStreamAttitudeQuaternion &); + +protected: + explicit MavlinkStreamAttitudeQuaternion(Mavlink *mavlink) : MavlinkStream(mavlink), + att_sub(nullptr), + att_time(0) + {} + + void subscribe() + { + att_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); + } + + void send(const hrt_abstime t) + { + struct vehicle_attitude_s att; + + if (att_sub->update(&att_time, &att)) { + mavlink_attitude_quaternion_t msg; + + msg.time_boot_ms = att.timestamp / 1000; + msg.q1 = att.q[0]; + msg.q2 = att.q[1]; + msg.q3 = att.q[2]; + msg.q4 = att.q[3]; + msg.rollspeed = att.rollspeed; + msg.pitchspeed = att.pitchspeed; + msg.yawspeed = att.yawspeed; + + _mavlink->send_message(MAVLINK_MSG_ID_ATTITUDE_QUATERNION, &msg); + } + } +}; + + +class MavlinkStreamVFRHUD : public MavlinkStream +{ +public: + + const char *get_name() const + { + return MavlinkStreamVFRHUD::get_name_static(); + } + + static const char *get_name_static() + { + return "VFR_HUD"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_VFR_HUD; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamVFRHUD(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_VFR_HUD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *att_sub; + uint64_t att_time; + + MavlinkOrbSubscription *pos_sub; + uint64_t pos_time; + + MavlinkOrbSubscription *armed_sub; + uint64_t armed_time; + + MavlinkOrbSubscription *act_sub; + uint64_t act_time; + + MavlinkOrbSubscription *airspeed_sub; + uint64_t airspeed_time; + + /* do not allow top copying this class */ + MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &); + MavlinkStreamVFRHUD& operator = (const MavlinkStreamVFRHUD &); + +protected: + explicit MavlinkStreamVFRHUD(Mavlink *mavlink) : MavlinkStream(mavlink), + att_sub(nullptr), + att_time(0), + pos_sub(nullptr), + pos_time(0), + armed_sub(nullptr), + armed_time(0), + act_sub(nullptr), + act_time(0), + airspeed_sub(nullptr), + airspeed_time(0) + {} + + void subscribe() + { + att_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); + pos_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); + armed_sub = _mavlink->add_orb_subscription(ORB_ID(actuator_armed)); + act_sub = _mavlink->add_orb_subscription(ORB_ID(actuator_controls_0)); + airspeed_sub = _mavlink->add_orb_subscription(ORB_ID(airspeed)); + } + + void send(const hrt_abstime t) + { + struct vehicle_attitude_s att; + struct vehicle_global_position_s pos; + struct actuator_armed_s armed; + struct actuator_controls_s act; + struct airspeed_s airspeed; + + bool updated = att_sub->update(&att_time, &att); + updated |= pos_sub->update(&pos_time, &pos); + updated |= armed_sub->update(&armed_time, &armed); + updated |= act_sub->update(&act_time, &act); + updated |= airspeed_sub->update(&airspeed_time, &airspeed); + + if (updated) { + mavlink_vfr_hud_t msg; + + msg.airspeed = airspeed.true_airspeed_m_s; + msg.groundspeed = sqrtf(pos.vel_n * pos.vel_n + pos.vel_e * pos.vel_e); + msg.heading = _wrap_2pi(att.yaw) * M_RAD_TO_DEG_F; + msg.throttle = armed.armed ? act.control[3] * 100.0f : 0.0f; + msg.alt = pos.alt; + msg.climb = -pos.vel_d; + + _mavlink->send_message(MAVLINK_MSG_ID_VFR_HUD, &msg); + } + } +}; + + //class MavlinkStreamGPSRawInt : public MavlinkStream //{ //public: @@ -818,9 +842,9 @@ protected: // gps_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// gps_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position)); +// gps_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position)); // } // // void send(const hrt_abstime t) @@ -886,10 +910,10 @@ protected: // home_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); -// home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); +// pos_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); +// home_sub = _mavlink->add_orb_subscription(ORB_ID(home_position)); // } // // void send(const hrt_abstime t) @@ -953,9 +977,9 @@ protected: // pos_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position)); +// pos_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_local_position)); // } // // void send(const hrt_abstime t) @@ -1014,9 +1038,9 @@ protected: // pos_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position)); +// pos_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position)); // } // // void send(const hrt_abstime t) @@ -1072,9 +1096,9 @@ protected: // home_sub(nullptr) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); +// home_sub = _mavlink->add_orb_subscription(ORB_ID(home_position)); // } // // void send(const hrt_abstime t) @@ -1144,7 +1168,7 @@ protected: // act_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { // orb_id_t act_topics[] = { // ORB_ID(actuator_outputs_0), @@ -1153,7 +1177,7 @@ protected: // ORB_ID(actuator_outputs_3) // }; // -// act_sub = mavlink->add_orb_subscription(act_topics[N]); +// act_sub = _mavlink->add_orb_subscription(act_topics[N]); // } // // void send(const hrt_abstime t) @@ -1224,11 +1248,11 @@ protected: // act_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); -// pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); -// act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0)); +// status_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); +// pos_sp_triplet_sub = _mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); +// act_sub = _mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0)); // } // // void send(const hrt_abstime t) @@ -1352,9 +1376,9 @@ protected: // pos_sp_triplet_sub(nullptr) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); +// pos_sp_triplet_sub = _mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); // } // // void send(const hrt_abstime t) @@ -1410,9 +1434,9 @@ protected: // pos_sp_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// pos_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint)); +// pos_sp_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint)); // } // // void send(const hrt_abstime t) @@ -1468,9 +1492,9 @@ protected: // att_sp_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// att_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint)); +// att_sp_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint)); // } // // void send(const hrt_abstime t) @@ -1526,9 +1550,9 @@ protected: // att_rates_sp_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// att_rates_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint)); +// att_rates_sp_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint)); // } // // void send(const hrt_abstime t) @@ -1584,9 +1608,9 @@ protected: // rc_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// rc_sub = mavlink->add_orb_subscription(ORB_ID(input_rc)); +// rc_sub = _mavlink->add_orb_subscription(ORB_ID(input_rc)); // } // // void send(const hrt_abstime t) @@ -1678,9 +1702,9 @@ protected: // manual_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// manual_sub = mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); +// manual_sub = _mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); // } // // void send(const hrt_abstime t) @@ -1737,9 +1761,9 @@ protected: // flow_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// flow_sub = mavlink->add_orb_subscription(ORB_ID(optical_flow)); +// flow_sub = _mavlink->add_orb_subscription(ORB_ID(optical_flow)); // } // // void send(const hrt_abstime t) @@ -1795,9 +1819,9 @@ protected: // att_ctrl_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// att_ctrl_sub = mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); +// att_ctrl_sub = _mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); // } // // void send(const hrt_abstime t) @@ -1863,9 +1887,9 @@ protected: // debug_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// debug_sub = mavlink->add_orb_subscription(ORB_ID(debug_key_value)); +// debug_sub = _mavlink->add_orb_subscription(ORB_ID(debug_key_value)); // } // // void send(const hrt_abstime t) @@ -1919,9 +1943,9 @@ protected: // status_sub(nullptr) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); +// status_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); // } // // void send(const hrt_abstime t) @@ -1979,9 +2003,9 @@ protected: // range_time(0) // {} // -// void subscribe(Mavlink *mavlink) +// void subscribe() // { -// range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder)); +// range_sub = _mavlink->add_orb_subscription(ORB_ID(sensor_range_finder)); // } // // void send(const hrt_abstime t) @@ -2014,9 +2038,9 @@ StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamCommandLong::new_instance, &MavlinkStreamCommandLong::get_name_static), new StreamListItem(&MavlinkStreamSysStatus::new_instance, &MavlinkStreamSysStatus::get_name_static), new StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static), -// new StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static), -// new StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static), -// new StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static), + new StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static), + new StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static), + new StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static), // new StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static), // new StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static), // new StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static), -- cgit v1.2.3 From ea2dce39927b7afcdfae79c059cc57342c70904e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 23 Jul 2014 23:10:10 +0200 Subject: mavlink: MavlinkStream API simplifyed --- src/modules/mavlink/mavlink_main.cpp | 1 - src/modules/mavlink/mavlink_messages.cpp | 171 ++++++++++++------------------- src/modules/mavlink/mavlink_parameters.h | 2 - src/modules/mavlink/mavlink_stream.h | 1 - 4 files changed, 66 insertions(+), 109 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index e49e99a9b..0cf708017 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -908,7 +908,6 @@ Mavlink::configure_stream(const char *stream_name, const float rate) /* create new instance */ stream = streams_list[i]->new_instance(this); stream->set_interval(interval); - stream->subscribe(); LL_APPEND(_streams, stream); return OK; diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 575268814..863b7a1d4 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -264,8 +264,8 @@ public: } private: - MavlinkOrbSubscription *status_sub; - MavlinkOrbSubscription *pos_sp_triplet_sub; + MavlinkOrbSubscription *_status_sub; + MavlinkOrbSubscription *_pos_sp_triplet_sub; /* do not allow top copying this class */ MavlinkStreamHeartbeat(MavlinkStreamHeartbeat &); @@ -273,28 +273,22 @@ private: protected: explicit MavlinkStreamHeartbeat(Mavlink *mavlink) : MavlinkStream(mavlink), - status_sub(nullptr), - pos_sp_triplet_sub(nullptr) + _status_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_status))), + _pos_sp_triplet_sub(_mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet))) {} - void subscribe() - { - status_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); - pos_sp_triplet_sub = _mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); - } - void send(const hrt_abstime t) { struct vehicle_status_s status; struct position_setpoint_triplet_s pos_sp_triplet; /* always send the heartbeat, independent of the update status of the topics */ - if (!status_sub->update(&status)) { + if (!_status_sub->update(&status)) { /* if topic update failed fill it with defaults */ memset(&status, 0, sizeof(status)); } - if (!pos_sp_triplet_sub->update(&pos_sp_triplet)) { + if (!_pos_sp_triplet_sub->update(&pos_sp_triplet)) { /* if topic update failed fill it with defaults */ memset(&pos_sp_triplet, 0, sizeof(pos_sp_triplet)); } @@ -347,14 +341,10 @@ private: protected: explicit MavlinkStreamCommandLong(Mavlink *mavlink) : MavlinkStream(mavlink), - _cmd_sub(nullptr), + _cmd_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_command))), _cmd_time(0) {} - void subscribe() { - _cmd_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_command)); - } - void send(const hrt_abstime t) { struct vehicle_command_s cmd; @@ -411,7 +401,7 @@ public: } private: - MavlinkOrbSubscription *status_sub; + MavlinkOrbSubscription *_status_sub; /* do not allow top copying this class */ MavlinkStreamSysStatus(MavlinkStreamSysStatus &); @@ -419,19 +409,14 @@ private: protected: explicit MavlinkStreamSysStatus(Mavlink *mavlink) : MavlinkStream(mavlink), - status_sub(nullptr) + _status_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_status))) {} - void subscribe() - { - status_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); - } - void send(const hrt_abstime t) { struct vehicle_status_s status; - if (status_sub->update(&status)) { + if (_status_sub->update(&status)) { mavlink_sys_status_t msg; msg.onboard_control_sensors_present = status.onboard_control_sensors_present; @@ -483,13 +468,13 @@ public: } private: - MavlinkOrbSubscription *sensor_sub; - uint64_t sensor_time; + MavlinkOrbSubscription *_sensor_sub; + uint64_t _sensor_time; - uint64_t accel_timestamp; - uint64_t gyro_timestamp; - uint64_t mag_timestamp; - uint64_t baro_timestamp; + uint64_t _accel_timestamp; + uint64_t _gyro_timestamp; + uint64_t _mag_timestamp; + uint64_t _baro_timestamp; /* do not allow top copying this class */ MavlinkStreamHighresIMU(MavlinkStreamHighresIMU &); @@ -497,48 +482,43 @@ private: protected: explicit MavlinkStreamHighresIMU(Mavlink *mavlink) : MavlinkStream(mavlink), - sensor_sub(nullptr), - sensor_time(0), - accel_timestamp(0), - gyro_timestamp(0), - mag_timestamp(0), - baro_timestamp(0) + _sensor_sub(_mavlink->add_orb_subscription(ORB_ID(sensor_combined))), + _sensor_time(0), + _accel_timestamp(0), + _gyro_timestamp(0), + _mag_timestamp(0), + _baro_timestamp(0) {} - void subscribe() - { - sensor_sub = _mavlink->add_orb_subscription(ORB_ID(sensor_combined)); - } - void send(const hrt_abstime t) { struct sensor_combined_s sensor; - if (sensor_sub->update(&sensor_time, &sensor)) { + if (_sensor_sub->update(&_sensor_time, &sensor)) { uint16_t fields_updated = 0; - if (accel_timestamp != sensor.accelerometer_timestamp) { + if (_accel_timestamp != sensor.accelerometer_timestamp) { /* mark first three dimensions as changed */ fields_updated |= (1 << 0) | (1 << 1) | (1 << 2); - accel_timestamp = sensor.accelerometer_timestamp; + _accel_timestamp = sensor.accelerometer_timestamp; } - if (gyro_timestamp != sensor.timestamp) { + if (_gyro_timestamp != sensor.timestamp) { /* mark second group dimensions as changed */ fields_updated |= (1 << 3) | (1 << 4) | (1 << 5); - gyro_timestamp = sensor.timestamp; + _gyro_timestamp = sensor.timestamp; } - if (mag_timestamp != sensor.magnetometer_timestamp) { + if (_mag_timestamp != sensor.magnetometer_timestamp) { /* mark third group dimensions as changed */ fields_updated |= (1 << 6) | (1 << 7) | (1 << 8); - mag_timestamp = sensor.magnetometer_timestamp; + _mag_timestamp = sensor.magnetometer_timestamp; } - if (baro_timestamp != sensor.baro_timestamp) { + if (_baro_timestamp != sensor.baro_timestamp) { /* mark last group dimensions as changed */ fields_updated |= (1 << 9) | (1 << 11) | (1 << 12); - baro_timestamp = sensor.baro_timestamp; + _baro_timestamp = sensor.baro_timestamp; } mavlink_highres_imu_t msg; @@ -594,8 +574,8 @@ public: } private: - MavlinkOrbSubscription *att_sub; - uint64_t att_time; + MavlinkOrbSubscription *_att_sub; + uint64_t _att_time; /* do not allow top copying this class */ MavlinkStreamAttitude(MavlinkStreamAttitude &); @@ -604,20 +584,15 @@ private: protected: explicit MavlinkStreamAttitude(Mavlink *mavlink) : MavlinkStream(mavlink), - att_sub(nullptr), - att_time(0) + _att_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude))), + _att_time(0) {} - void subscribe() - { - att_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); - } - void send(const hrt_abstime t) { struct vehicle_attitude_s att; - if (att_sub->update(&att_time, &att)) { + if (_att_sub->update(&_att_time, &att)) { mavlink_attitude_t msg; msg.time_boot_ms = att.timestamp / 1000; @@ -663,8 +638,8 @@ public: } private: - MavlinkOrbSubscription *att_sub; - uint64_t att_time; + MavlinkOrbSubscription *_att_sub; + uint64_t _att_time; /* do not allow top copying this class */ MavlinkStreamAttitudeQuaternion(MavlinkStreamAttitudeQuaternion &); @@ -672,20 +647,15 @@ private: protected: explicit MavlinkStreamAttitudeQuaternion(Mavlink *mavlink) : MavlinkStream(mavlink), - att_sub(nullptr), - att_time(0) + _att_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude))), + _att_time(0) {} - void subscribe() - { - att_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); - } - void send(const hrt_abstime t) { struct vehicle_attitude_s att; - if (att_sub->update(&att_time, &att)) { + if (_att_sub->update(&_att_time, &att)) { mavlink_attitude_quaternion_t msg; msg.time_boot_ms = att.timestamp / 1000; @@ -733,20 +703,20 @@ public: } private: - MavlinkOrbSubscription *att_sub; - uint64_t att_time; + MavlinkOrbSubscription *_att_sub; + uint64_t _att_time; - MavlinkOrbSubscription *pos_sub; - uint64_t pos_time; + MavlinkOrbSubscription *_pos_sub; + uint64_t _pos_time; - MavlinkOrbSubscription *armed_sub; - uint64_t armed_time; + MavlinkOrbSubscription *_armed_sub; + uint64_t _armed_time; - MavlinkOrbSubscription *act_sub; - uint64_t act_time; + MavlinkOrbSubscription *_act_sub; + uint64_t _act_time; - MavlinkOrbSubscription *airspeed_sub; - uint64_t airspeed_time; + MavlinkOrbSubscription *_airspeed_sub; + uint64_t _airspeed_time; /* do not allow top copying this class */ MavlinkStreamVFRHUD(MavlinkStreamVFRHUD &); @@ -754,27 +724,18 @@ private: protected: explicit MavlinkStreamVFRHUD(Mavlink *mavlink) : MavlinkStream(mavlink), - att_sub(nullptr), - att_time(0), - pos_sub(nullptr), - pos_time(0), - armed_sub(nullptr), - armed_time(0), - act_sub(nullptr), - act_time(0), - airspeed_sub(nullptr), - airspeed_time(0) + _att_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude))), + _att_time(0), + _pos_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_global_position))), + _pos_time(0), + _armed_sub(_mavlink->add_orb_subscription(ORB_ID(actuator_armed))), + _armed_time(0), + _act_sub(_mavlink->add_orb_subscription(ORB_ID(actuator_controls_0))), + _act_time(0), + _airspeed_sub(_mavlink->add_orb_subscription(ORB_ID(airspeed))), + _airspeed_time(0) {} - void subscribe() - { - att_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); - pos_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); - armed_sub = _mavlink->add_orb_subscription(ORB_ID(actuator_armed)); - act_sub = _mavlink->add_orb_subscription(ORB_ID(actuator_controls_0)); - airspeed_sub = _mavlink->add_orb_subscription(ORB_ID(airspeed)); - } - void send(const hrt_abstime t) { struct vehicle_attitude_s att; @@ -783,11 +744,11 @@ protected: struct actuator_controls_s act; struct airspeed_s airspeed; - bool updated = att_sub->update(&att_time, &att); - updated |= pos_sub->update(&pos_time, &pos); - updated |= armed_sub->update(&armed_time, &armed); - updated |= act_sub->update(&act_time, &act); - updated |= airspeed_sub->update(&airspeed_time, &airspeed); + bool updated = _att_sub->update(&_att_time, &att); + updated |= _pos_sub->update(&_pos_time, &pos); + updated |= _armed_sub->update(&_armed_time, &armed); + updated |= _act_sub->update(&_act_time, &act); + updated |= _airspeed_sub->update(&_airspeed_time, &airspeed); if (updated) { mavlink_vfr_hud_t msg; diff --git a/src/modules/mavlink/mavlink_parameters.h b/src/modules/mavlink/mavlink_parameters.h index 2a5a205e9..5576e6b84 100644 --- a/src/modules/mavlink/mavlink_parameters.h +++ b/src/modules/mavlink/mavlink_parameters.h @@ -109,8 +109,6 @@ private: protected: explicit MavlinkParametersManager(Mavlink *mavlink); - void subscribe() {} - void send(const hrt_abstime t); void send_param(param_t param); diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h index 646931c07..ef22dc443 100644 --- a/src/modules/mavlink/mavlink_stream.h +++ b/src/modules/mavlink/mavlink_stream.h @@ -75,7 +75,6 @@ public: int update(const hrt_abstime t); static MavlinkStream *new_instance(const Mavlink *mavlink); static const char *get_name_static(); - virtual void subscribe() = 0; virtual const char *get_name() const = 0; virtual uint8_t get_id() = 0; -- cgit v1.2.3 From 9df1da1b7cd140e9452c73c6307befeadd6ce4c5 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 24 Jul 2014 12:10:21 +0200 Subject: mavlink: STATUSTEXT implemented via streams API --- src/modules/mavlink/mavlink_main.cpp | 72 +++++--------------- src/modules/mavlink/mavlink_main.h | 18 +++-- src/modules/mavlink/mavlink_messages.cpp | 110 ++++++++++++++++++++++++++----- 3 files changed, 119 insertions(+), 81 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 0cf708017..7d3fb97e1 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -452,7 +452,6 @@ Mavlink::mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg) case (int)MAVLINK_IOC_SEND_TEXT_EMERGENCY: { const char *txt = (const char *)arg; -// printf("logmsg: %s\n", txt); struct mavlink_logmessage msg; strncpy(msg.text, txt, sizeof(msg.text)); msg.severity = (unsigned char)cmd; @@ -782,67 +781,32 @@ Mavlink::handle_message(const mavlink_message_t *msg) } } -int +void Mavlink::send_statustext_info(const char *string) { - return send_statustext(MAVLINK_IOC_SEND_TEXT_INFO, string); + send_statustext(MAVLINK_IOC_SEND_TEXT_INFO, string); } -int +void Mavlink::send_statustext_critical(const char *string) { - return send_statustext(MAVLINK_IOC_SEND_TEXT_CRITICAL, string); + send_statustext(MAVLINK_IOC_SEND_TEXT_CRITICAL, string); } -int +void Mavlink::send_statustext_emergency(const char *string) { - return send_statustext(MAVLINK_IOC_SEND_TEXT_EMERGENCY, string); + send_statustext(MAVLINK_IOC_SEND_TEXT_EMERGENCY, string); } -int +void Mavlink::send_statustext(unsigned severity, const char *string) { - const int len = MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN; - mavlink_statustext_t statustext; - - int i = 0; - - while (i < len - 1) { - statustext.text[i] = string[i]; - - if (string[i] == '\0') { - break; - } - - i++; - } - - if (i > 1) { - /* Enforce null termination */ - statustext.text[i] = '\0'; + struct mavlink_logmessage logmsg; + strncpy(logmsg.text, string, sizeof(logmsg.text)); + logmsg.severity = severity; - /* Map severity */ - switch (severity) { - case MAVLINK_IOC_SEND_TEXT_INFO: - statustext.severity = MAV_SEVERITY_INFO; - break; - - case MAVLINK_IOC_SEND_TEXT_CRITICAL: - statustext.severity = MAV_SEVERITY_CRITICAL; - break; - - case MAVLINK_IOC_SEND_TEXT_EMERGENCY: - statustext.severity = MAV_SEVERITY_EMERGENCY; - break; - } - - send_message(MAVLINK_MSG_ID_STATUSTEXT, &statustext); - return OK; - - } else { - return ERROR; - } + mavlink_logbuffer_write(&_logbuffer, &logmsg); } MavlinkOrbSubscription *Mavlink::add_orb_subscription(const orb_id_t topic) @@ -1312,6 +1276,9 @@ Mavlink::task_main(int argc, char *argv[]) /* HEARTBEAT is constant rate stream, rate never adjusted */ configure_stream("HEARTBEAT", 1.0f); + /* STATUSTEXT stream is like normal stream but gets messages from logbuffer instead of uORB */ + configure_stream("STATUSTEXT", 20.0f); + /* COMMAND_LONG stream: use high rate to avoid commands skipping */ configure_stream("COMMAND_LONG", 100.0f); @@ -1367,7 +1334,7 @@ Mavlink::task_main(int argc, char *argv[]) hrt_abstime t = hrt_absolute_time(); update_rate_mult(); - warnx("rate mult %.2f", (double)_rate_mult); + warnx("rate mult %.2f rate %.3f err %.3f", (double)_rate_mult, (double)_rate_tx, (double)_rate_txerr); if (param_sub->update(¶m_time, nullptr)) { /* parameters updated */ @@ -1407,15 +1374,6 @@ Mavlink::task_main(int argc, char *argv[]) if (fast_rate_limiter.check(t)) { // TODO missions //_mission_manager->eventloop(); - - if (!mavlink_logbuffer_is_empty(&_logbuffer)) { - struct mavlink_logmessage msg; - int lb_ret = mavlink_logbuffer_read(&_logbuffer, &msg); - - if (lb_ret == OK) { - send_statustext(msg.severity, msg.text); - } - } } /* pass messages from other UARTs or FTP worker */ diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 7fcbae72e..87bb9d9ad 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -188,29 +188,33 @@ public: * * @param string the message to send (will be capped by mavlink max string length) */ - int send_statustext_info(const char *string); + void send_statustext_info(const char *string); /** * Send a status text with loglevel CRITICAL * * @param string the message to send (will be capped by mavlink max string length) */ - int send_statustext_critical(const char *string); + void send_statustext_critical(const char *string); /** * Send a status text with loglevel EMERGENCY * * @param string the message to send (will be capped by mavlink max string length) */ - int send_statustext_emergency(const char *string); + void send_statustext_emergency(const char *string); /** - * Send a status text with loglevel + * Send a status text with loglevel, the difference from mavlink_log_xxx() is that message sent + * only on this mavlink connection. Useful for reporting communication specific, not system-wide info + * only to client interested in it. Message will be not sent immediately but queued in buffer as + * for mavlink_log_xxx(). * * @param string the message to send (will be capped by mavlink max string length) - * @param severity the log level, one of + * @param severity the log level */ - int send_statustext(unsigned severity, const char *string); + void send_statustext(unsigned severity, const char *string); + MavlinkStream * get_streams() const { return _streams; } float get_rate_mult(); @@ -259,6 +263,8 @@ public: */ struct telemetry_status_s& get_rx_status() { return _rstatus; } + struct mavlink_logbuffer *get_logbuffer() { return &_logbuffer; } + protected: Mavlink *next; diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 863b7a1d4..4333369fe 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -40,9 +40,9 @@ */ #include + #include #include - #include #include #include @@ -72,8 +72,8 @@ #include #include #include - #include +#include #include "mavlink_messages.h" #include "mavlink_main.h" @@ -306,6 +306,77 @@ protected: } }; +class MavlinkStreamStatustext : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamStatustext::get_name_static(); + } + + static const char *get_name_static() + { + return "STATUSTEXT"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_STATUSTEXT; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamStatustext(mavlink); + } + + unsigned get_size() { + return mavlink_logbuffer_is_empty(_mavlink->get_logbuffer()) ? 0 : (MAVLINK_MSG_ID_STATUSTEXT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES); + } + +private: + /* do not allow top copying this class */ + MavlinkStreamStatustext(MavlinkStreamStatustext &); + MavlinkStreamStatustext& operator = (const MavlinkStreamStatustext &); + +protected: + explicit MavlinkStreamStatustext(Mavlink *mavlink) : MavlinkStream(mavlink) + {} + + void send(const hrt_abstime t) + { + if (!mavlink_logbuffer_is_empty(_mavlink->get_logbuffer())) { + struct mavlink_logmessage logmsg; + int lb_ret = mavlink_logbuffer_read(_mavlink->get_logbuffer(), &logmsg); + + if (lb_ret == OK) { + mavlink_statustext_t msg; + + /* map severity */ + switch (logmsg.severity) { + case MAVLINK_IOC_SEND_TEXT_INFO: + msg.severity = MAV_SEVERITY_INFO; + break; + + case MAVLINK_IOC_SEND_TEXT_CRITICAL: + msg.severity = MAV_SEVERITY_CRITICAL; + break; + + case MAVLINK_IOC_SEND_TEXT_EMERGENCY: + msg.severity = MAV_SEVERITY_EMERGENCY; + break; + + default: + msg.severity = MAV_SEVERITY_INFO; + break; + } + strncpy(msg.text, logmsg.text, sizeof(msg.text)); + + _mavlink->send_message(MAVLINK_MSG_ID_STATUSTEXT, &msg); + } + } + } +}; + class MavlinkStreamCommandLong : public MavlinkStream { public: @@ -329,7 +400,9 @@ public: return new MavlinkStreamCommandLong(mavlink); } - unsigned get_size() { return 0; } // commands stream is not regular and not predictable + unsigned get_size() { + return 0; // commands stream is not regular and not predictable + } private: MavlinkOrbSubscription *_cmd_sub; @@ -352,21 +425,21 @@ protected: if (_cmd_sub->update(&_cmd_time, &cmd)) { /* only send commands for other systems/components */ if (cmd.target_system != mavlink_system.sysid || cmd.target_component != mavlink_system.compid) { - mavlink_command_long_t mavcmd; - - mavcmd.target_system = cmd.target_system; - mavcmd.target_component = cmd.target_component; - mavcmd.command = cmd.command; - mavcmd.confirmation = cmd.confirmation; - mavcmd.param1 = cmd.param1; - mavcmd.param2 = cmd.param2; - mavcmd.param3 = cmd.param3; - mavcmd.param4 = cmd.param4; - mavcmd.param5 = cmd.param5; - mavcmd.param6 = cmd.param6; - mavcmd.param7 = cmd.param7; - - _mavlink->send_message(MAVLINK_MSG_ID_COMMAND_LONG, &mavcmd); + mavlink_command_long_t msg; + + msg.target_system = cmd.target_system; + msg.target_component = cmd.target_component; + msg.command = cmd.command; + msg.confirmation = cmd.confirmation; + msg.param1 = cmd.param1; + msg.param2 = cmd.param2; + msg.param3 = cmd.param3; + msg.param4 = cmd.param4; + msg.param5 = cmd.param5; + msg.param6 = cmd.param6; + msg.param7 = cmd.param7; + + _mavlink->send_message(MAVLINK_MSG_ID_COMMAND_LONG, &msg); } } } @@ -1996,6 +2069,7 @@ protected: StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static), + new StreamListItem(&MavlinkStreamStatustext::new_instance, &MavlinkStreamStatustext::get_name_static), new StreamListItem(&MavlinkStreamCommandLong::new_instance, &MavlinkStreamCommandLong::get_name_static), new StreamListItem(&MavlinkStreamSysStatus::new_instance, &MavlinkStreamSysStatus::get_name_static), new StreamListItem(&MavlinkStreamHighresIMU::new_instance, &MavlinkStreamHighresIMU::get_name_static), -- cgit v1.2.3 From eb4015ced1b55a280fe93e10811c0dad5c719438 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 24 Jul 2014 12:10:56 +0200 Subject: mavlink: strange FIXME comment removed --- src/modules/mavlink/mavlink_mission.h | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h index b792b9aaf..5bf80768c 100644 --- a/src/modules/mavlink/mavlink_mission.h +++ b/src/modules/mavlink/mavlink_mission.h @@ -46,7 +46,6 @@ #include "mavlink_rate_limiter.h" #include -// FIXME XXX - TO BE MOVED TO XML enum MAVLINK_WPM_STATES { MAVLINK_WPM_STATE_IDLE = 0, MAVLINK_WPM_STATE_SENDLIST, -- cgit v1.2.3 From 897984c4f4a43136320c39f75fef106d3447ce47 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 24 Jul 2014 12:28:02 +0200 Subject: mavlink: bug fixed, don't delete parameters stream --- src/modules/mavlink/mavlink_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 7d3fb97e1..44329e0d2 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1443,7 +1443,6 @@ Mavlink::task_main(int argc, char *argv[]) } delete _mission_manager; - delete _parameters_manager; delete _subscribe_to_stream; _subscribe_to_stream = nullptr; -- cgit v1.2.3 From 87334a987a5b571f6cc3d962df1194584de4fd7f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 24 Jul 2014 17:42:45 +0200 Subject: Return 0 for a non-reset --- src/modules/ekf_att_pos_estimator/estimator_23states.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index 768e0be35..3d504d395 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -2773,7 +2773,7 @@ int AttPosEKF::CheckAndBound(struct ekf_status_report *last_error) ResetHeight(); ResetStoredStates(); - ret = 3; + ret = 0; } // Reset the filter if gyro offsets are excessive -- cgit v1.2.3 From f03f6ddd74b1aca710f4675bbee18608eeea1f08 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 24 Jul 2014 17:57:15 +0200 Subject: Improve user feedback on mission load fails --- src/modules/navigator/mission.cpp | 36 +++++++++++++++++++++--------------- 1 file changed, 21 insertions(+), 15 deletions(-) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index ba766cd10..12f6b9c21 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -314,30 +314,36 @@ Mission::set_mission_items() /* set previous position setpoint to current */ set_previous_pos_setpoint(); + /* get home distance state */ + bool home_dist_ok = check_dist_1wp(); + /* the home dist check provides user feedback, so we initialize it to this */ + bool user_feedback_done = !home_dist_ok; + /* try setting onboard mission item */ if (_param_onboard_enabled.get() && read_mission_item(true, true, &_mission_item)) { /* if mission type changed, notify */ if (_mission_type != MISSION_TYPE_ONBOARD) { - mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: onboard mission running"); + mavlink_log_critical(_navigator->get_mavlink_fd(), "onboard mission now running"); } _mission_type = MISSION_TYPE_ONBOARD; /* try setting offboard mission item */ - } else if (check_dist_1wp() && read_mission_item(false, true, &_mission_item)) { + } else if (home_dist_ok && read_mission_item(false, true, &_mission_item)) { /* if mission type changed, notify */ if (_mission_type != MISSION_TYPE_OFFBOARD) { - mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: offboard mission running"); + mavlink_log_critical(_navigator->get_mavlink_fd(), "offboard mission now running"); } _mission_type = MISSION_TYPE_OFFBOARD; } else { - /* no mission available, switch to loiter */ + /* no mission available or mission finished, switch to loiter */ if (_mission_type != MISSION_TYPE_NONE) { - mavlink_log_info(_navigator->get_mavlink_fd(), - "#audio: mission finished"); - } else { - mavlink_log_info(_navigator->get_mavlink_fd(), - "#audio: no mission available"); + mavlink_log_critical(_navigator->get_mavlink_fd(), "mission finished, loitering"); + } else if (!user_feedback_done) { + /* only tell users that we got no mission if there has not been any + * better, more specific feedback yet + */ + mavlink_log_critical(_navigator->get_mavlink_fd(), "no valid mission available"); } _mission_type = MISSION_TYPE_NONE; @@ -397,7 +403,7 @@ Mission::set_mission_items() takeoff_alt = fmaxf(takeoff_alt, _navigator->get_home_position()->alt + _param_takeoff_alt.get()); } - mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: takeoff to %.1fm above home", (double)(takeoff_alt - _navigator->get_home_position()->alt)); + mavlink_log_critical(_navigator->get_mavlink_fd(), "takeoff to %.1f meters above home", (double)(takeoff_alt - _navigator->get_home_position()->alt)); _mission_item.lat = _navigator->get_global_position()->lat; _mission_item.lon = _navigator->get_global_position()->lon; @@ -483,7 +489,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s if (dm_read(dm_item, *mission_index_ptr, &mission_item_tmp, len) != len) { /* not supposed to happen unless the datamanager can't access the SD card, etc. */ mavlink_log_critical(_navigator->get_mavlink_fd(), - "#audio: ERROR waypoint could not be read"); + "ERROR waypoint could not be read"); return false; } @@ -502,7 +508,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s /* not supposed to happen unless the datamanager can't access the * dataman */ mavlink_log_critical(_navigator->get_mavlink_fd(), - "#audio: ERROR DO JUMP waypoint could not be written"); + "ERROR DO JUMP waypoint could not be written"); return false; } } @@ -511,8 +517,8 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s *mission_index_ptr = mission_item_tmp.do_jump_mission_index; } else { - mavlink_log_info(_navigator->get_mavlink_fd(), - "#audio: DO JUMP repetitions completed"); + mavlink_log_critical(_navigator->get_mavlink_fd(), + "DO JUMP repetitions completed"); /* no more DO_JUMPS, therefore just try to continue with next mission item */ (*mission_index_ptr)++; } @@ -526,7 +532,7 @@ Mission::read_mission_item(bool onboard, bool is_current, struct mission_item_s /* we have given up, we don't want to cycle forever */ mavlink_log_critical(_navigator->get_mavlink_fd(), - "#audio: ERROR DO JUMP is cycling, giving up"); + "ERROR DO JUMP is cycling, giving up"); return false; } -- cgit v1.2.3 From b4e6f535ea15055f39b122eb87004c97796eb584 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 24 Jul 2014 17:57:30 +0200 Subject: mavlink: onboard links should only pass on messages from the same system ID --- src/modules/mavlink/mavlink_main.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 0c6f8c42f..8cb0152fd 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -483,7 +483,12 @@ Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self) Mavlink *inst; LL_FOREACH(_mavlink_instances, inst) { if (inst != self) { - inst->pass_message(msg); + + /* if not in normal mode, we are an onboard link + * onboard links should only pass on messages from the same system ID */ + if(!(self->_mode != MAVLINK_MODE_NORMAL && msg->sysid != mavlink_system.sysid)) { + inst->pass_message(msg); + } } } } -- cgit v1.2.3 From 36d8d73aeb7ef214979a64960df727bf3bab048c Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 24 Jul 2014 17:58:17 +0200 Subject: mavlink: use correct component ID --- src/modules/mavlink/mavlink_messages.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 6885bebde..92e469619 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1832,11 +1832,11 @@ protected: || status.arming_state == ARMING_STATE_ARMED_ERROR) { /* send camera capture on */ - mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0); + mavlink_msg_command_long_send(_channel, mavlink_system.sysid, mavlink_system.compid, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0); } else { /* send camera capture off */ - mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0); + mavlink_msg_command_long_send(_channel, mavlink_system.sysid, mavlink_system.compid, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0); } } }; -- cgit v1.2.3 From 58aa9f28f060f7adf7955b39d72ac972c03f1348 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 24 Jul 2014 17:59:02 +0200 Subject: mavlink: when detecting spoof, be more verbose --- src/modules/mavlink/mavlink_receiver.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 54c412ce7..69e3ef31d 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -241,7 +241,8 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg) } else { if (msg->sysid == mavlink_system.sysid && msg->compid == mavlink_system.compid) { - warnx("ignoring CMD spoofed with same SYS/COMP ID"); + warnx("ignoring CMD spoofed with same SYS/COMP (%d/%d) ID", + mavlink_system.sysid, mavlink_system.compid); return; } -- cgit v1.2.3 From b31ddc193c0e3dff3a8e4b4c343848f0f64e61ed Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 24 Jul 2014 19:31:25 +0200 Subject: mavlink: tix mission manager to use MavlinkStream API --- src/modules/mavlink/mavlink_main.cpp | 27 ++---- src/modules/mavlink/mavlink_main.h | 2 - src/modules/mavlink/mavlink_mission.cpp | 25 ++++-- src/modules/mavlink/mavlink_mission.h | 118 +++++++++++++++------------ src/modules/mavlink/mavlink_rate_limiter.cpp | 2 +- 5 files changed, 97 insertions(+), 77 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 44329e0d2..df078325a 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -131,8 +131,6 @@ Mavlink::Mavlink() : _streams(nullptr), _mission_manager(nullptr), _parameters_manager(nullptr), - _mission_pub(-1), - _mission_result_sub(-1), _mode(MAVLINK_MODE_NORMAL), _channel(MAVLINK_COMM_0), _logbuffer {}, @@ -1255,12 +1253,6 @@ Mavlink::task_main(int argc, char *argv[]) /* start the MAVLink receiver */ _receive_thread = MavlinkReceiver::receive_start(this); - _mission_result_sub = orb_subscribe(ORB_ID(mission_result)); - - /* create mission manager */ - _mission_manager = new MavlinkMissionManager(this); - _mission_manager->set_verbose(_verbose); - _task_running = true; MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update)); @@ -1287,6 +1279,14 @@ Mavlink::task_main(int argc, char *argv[]) _parameters_manager->set_interval(interval_from_rate(30.0f)); LL_APPEND(_streams, _parameters_manager); + /* MISSION_STREAM stream, actually sends all MISSION_XXX messages at some rate depending on + * remote requests rate. Rate specified here controls how much bandwidth we will reserve for + * mission messages. */ + _mission_manager = (MavlinkMissionManager *) MavlinkMissionManager::new_instance(this); + _mission_manager->set_interval(interval_from_rate(10.0f)); + _mission_manager->set_verbose(_verbose); + LL_APPEND(_streams, _mission_manager); + switch (_mode) { case MAVLINK_MODE_NORMAL: configure_stream("SYS_STATUS", 1.0f); @@ -1315,12 +1315,8 @@ Mavlink::task_main(int argc, char *argv[]) break; } - float base_rate_mult = _datarate / 1000.0f; - - MavlinkRateLimiter fast_rate_limiter(30000.0f / base_rate_mult); - /* set main loop delay depending on data rate to minimize CPU overhead */ - _main_loop_delay = MAIN_LOOP_DELAY / base_rate_mult; + _main_loop_delay = MAIN_LOOP_DELAY * 1000 / _datarate; /* now the instance is fully initialized and we can bump the instance count */ LL_APPEND(_mavlink_instances, this); @@ -1371,11 +1367,6 @@ Mavlink::task_main(int argc, char *argv[]) stream->update(t); } - if (fast_rate_limiter.check(t)) { - // TODO missions - //_mission_manager->eventloop(); - } - /* pass messages from other UARTs or FTP worker */ if (_passing_on || _ftp_on) { diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 87bb9d9ad..e3bad828f 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -289,8 +289,6 @@ private: MavlinkMissionManager *_mission_manager; MavlinkParametersManager *_parameters_manager; - orb_advert_t _mission_pub; - int _mission_result_sub; MAVLINK_MODE _mode; mavlink_channel_t _channel; diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp index d17ccc6f9..7a761588a 100644 --- a/src/modules/mavlink/mavlink_mission.cpp +++ b/src/modules/mavlink/mavlink_mission.cpp @@ -59,8 +59,7 @@ static const int ERROR = -1; -MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : - _mavlink(mavlink), +MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : MavlinkStream(mavlink), _state(MAVLINK_WPM_STATE_IDLE), _time_last_recv(0), _time_last_sent(0), @@ -79,9 +78,8 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) : _offboard_mission_sub(-1), _mission_result_sub(-1), _offboard_mission_pub(-1), - _slow_rate_limiter(2000000.0f / mavlink->get_rate_mult()), + _slow_rate_limiter(_interval / 10.0f), _verbose(false), - _channel(mavlink->get_channel()), _comp_id(MAV_COMP_ID_MISSIONPLANNER) { _offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission)); @@ -96,6 +94,20 @@ MavlinkMissionManager::~MavlinkMissionManager() close(_mission_result_sub); } +unsigned +MavlinkMissionManager::get_size() +{ + if (_state == MAVLINK_WPM_STATE_SENDLIST) { + return MAVLINK_MSG_ID_MISSION_ITEM_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + + } else if (_state == MAVLINK_WPM_STATE_GETLIST) { + return MAVLINK_MSG_ID_MISSION_REQUEST + MAVLINK_NUM_NON_PAYLOAD_BYTES; + + } else { + return 0; + } +} + void MavlinkMissionManager::init_offboard_mission() { @@ -275,9 +287,10 @@ MavlinkMissionManager::send_mission_item_reached(uint16_t seq) void -MavlinkMissionManager::eventloop() +MavlinkMissionManager::send(const hrt_abstime now) { - hrt_abstime now = hrt_absolute_time(); + /* update interval for slow rate limiter */ + _slow_rate_limiter.set_interval(_interval * 10 / _mavlink->get_rate_mult()); bool updated = false; orb_check(_mission_result_sub, &updated); diff --git a/src/modules/mavlink/mavlink_mission.h b/src/modules/mavlink/mavlink_mission.h index 5bf80768c..8ff27f87d 100644 --- a/src/modules/mavlink/mavlink_mission.h +++ b/src/modules/mavlink/mavlink_mission.h @@ -42,9 +42,11 @@ #pragma once +#include + #include "mavlink_bridge_header.h" #include "mavlink_rate_limiter.h" -#include +#include "mavlink_stream.h" enum MAVLINK_WPM_STATES { MAVLINK_WPM_STATE_IDLE = 0, @@ -65,20 +67,75 @@ enum MAVLINK_WPM_CODES { #define MAVLINK_MISSION_PROTOCOL_TIMEOUT_DEFAULT 5000000 ///< Protocol communication action timeout in useconds #define MAVLINK_MISSION_RETRY_TIMEOUT_DEFAULT 500000 ///< Protocol communication retry timeout in useconds -class Mavlink; - -class MavlinkMissionManager { +class MavlinkMissionManager : public MavlinkStream { public: - MavlinkMissionManager(Mavlink *parent); - ~MavlinkMissionManager(); + const char *get_name() const + { + return MavlinkMissionManager::get_name_static(); + } + + static const char *get_name_static() + { + return "MISSION_ITEM"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_MISSION_ITEM; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkMissionManager(mavlink); + } + + unsigned get_size(); + + void handle_message(const mavlink_message_t *msg); + + void set_verbose(bool v) { _verbose = v; } + +private: + enum MAVLINK_WPM_STATES _state; ///< Current state + + uint64_t _time_last_recv; + uint64_t _time_last_sent; + + uint32_t _action_timeout; + uint32_t _retry_timeout; + unsigned _max_count; ///< Maximum number of mission items + + int _dataman_id; ///< Dataman storage ID for active mission + unsigned _count; ///< Count of items in active mission + int _current_seq; ///< Current item sequence in active mission + + int _transfer_dataman_id; ///< Dataman storage ID for current transmission + unsigned _transfer_count; ///< Items count in current transmission + unsigned _transfer_seq; ///< Item sequence in current transmission + unsigned _transfer_current_seq; ///< Current item ID for current transmission (-1 means not initialized) + unsigned _transfer_partner_sysid; ///< Partner system ID for current transmission + unsigned _transfer_partner_compid; ///< Partner component ID for current transmission + + int _offboard_mission_sub; + int _mission_result_sub; + orb_advert_t _offboard_mission_pub; + + MavlinkRateLimiter _slow_rate_limiter; + + bool _verbose; + + uint8_t _comp_id; + + /* do not allow top copying this class */ + MavlinkMissionManager(MavlinkMissionManager &); + MavlinkMissionManager& operator = (const MavlinkMissionManager &); + void init_offboard_mission(); int update_active_mission(int dataman_id, unsigned count, int seq); - void send_message(mavlink_message_t *msg); - /** * @brief Sends an waypoint ack message */ @@ -110,10 +167,6 @@ public: */ void send_mission_item_reached(uint16_t seq); - void eventloop(); - - void handle_message(const mavlink_message_t *msg); - void handle_mission_ack(const mavlink_message_t *msg); void handle_mission_set_current(const mavlink_message_t *msg); @@ -138,43 +191,8 @@ public: */ int format_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item); - void set_verbose(bool v) { _verbose = v; } - -private: - Mavlink* _mavlink; - - enum MAVLINK_WPM_STATES _state; ///< Current state - - uint64_t _time_last_recv; - uint64_t _time_last_sent; - - uint32_t _action_timeout; - uint32_t _retry_timeout; - unsigned _max_count; ///< Maximum number of mission items - - int _dataman_id; ///< Dataman storage ID for active mission - unsigned _count; ///< Count of items in active mission - int _current_seq; ///< Current item sequence in active mission - - int _transfer_dataman_id; ///< Dataman storage ID for current transmission - unsigned _transfer_count; ///< Items count in current transmission - unsigned _transfer_seq; ///< Item sequence in current transmission - unsigned _transfer_current_seq; ///< Current item ID for current transmission (-1 means not initialized) - unsigned _transfer_partner_sysid; ///< Partner system ID for current transmission - unsigned _transfer_partner_compid; ///< Partner component ID for current transmission - - int _offboard_mission_sub; - int _mission_result_sub; - orb_advert_t _offboard_mission_pub; - - MavlinkRateLimiter _slow_rate_limiter; - - bool _verbose; - - mavlink_channel_t _channel; - uint8_t _comp_id; +protected: + explicit MavlinkMissionManager(Mavlink *mavlink); - /* do not allow copying this class */ - MavlinkMissionManager(const MavlinkMissionManager&); - MavlinkMissionManager operator=(const MavlinkMissionManager&); + void send(const hrt_abstime t); }; diff --git a/src/modules/mavlink/mavlink_rate_limiter.cpp b/src/modules/mavlink/mavlink_rate_limiter.cpp index 9cdda8b17..d3b3e1cde 100644 --- a/src/modules/mavlink/mavlink_rate_limiter.cpp +++ b/src/modules/mavlink/mavlink_rate_limiter.cpp @@ -64,7 +64,7 @@ MavlinkRateLimiter::check(hrt_abstime t) uint64_t dt = t - _last_sent; if (dt > 0 && dt >= _interval) { - _last_sent = (t / _interval) * _interval; + _last_sent = t; return true; } -- cgit v1.2.3 From c486aa536f3c0169e1abb0f4c2b60baa1e2b053b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 24 Jul 2014 19:34:19 +0200 Subject: mavlink: bug fixed, don't delete mission manages twice --- src/modules/mavlink/mavlink_main.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index df078325a..e27a940cf 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1433,8 +1433,6 @@ Mavlink::task_main(int argc, char *argv[]) perf_end(_loop_perf); } - delete _mission_manager; - delete _subscribe_to_stream; _subscribe_to_stream = nullptr; -- cgit v1.2.3 From 53f1b3190215f373aa5d8d38264b4ba5771b1676 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 24 Jul 2014 21:41:09 +0200 Subject: Do not abort on submodule init feedback --- Tools/check_submodules.sh | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/check_submodules.sh b/Tools/check_submodules.sh index 0c03396e7..3904a2775 100755 --- a/Tools/check_submodules.sh +++ b/Tools/check_submodules.sh @@ -73,8 +73,8 @@ then exit 1 fi else - git submodule init - git submodule update + git submodule init; + git submodule update; fi exit 0 -- cgit v1.2.3 From b72e89697c564c878c4e17c46b435e8fe94736c5 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 25 Jul 2014 00:52:42 +0400 Subject: UAVCAN update for #1229 --- uavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uavcan b/uavcan index dca2611c3..f51ee9cde 160000 --- a/uavcan +++ b/uavcan @@ -1 +1 @@ -Subproject commit dca2611c3186eaa1cac42557f07b013e2dc633d3 +Subproject commit f51ee9cdecd7841f6208bfb0b16228888daad663 -- cgit v1.2.3 From fd52e5561eaf14f9c6ca1abc00cb82b0e3d38ec8 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 24 Jul 2014 23:46:39 +0200 Subject: update comment about condition_global_position_valid --- src/modules/uORB/topics/vehicle_status.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h index b46c00b75..cbb148eda 100644 --- a/src/modules/uORB/topics/vehicle_status.h +++ b/src/modules/uORB/topics/vehicle_status.h @@ -186,7 +186,7 @@ struct vehicle_status_s { bool condition_system_sensors_initialized; bool condition_system_returned_to_home; bool condition_auto_mission_available; - bool condition_global_position_valid; /**< set to true by the commander app if the quality of the gps signal is good enough to use it in the position estimator */ + bool condition_global_position_valid; /**< set to true by the commander app if the quality of the position estimate is good enough to use it for navigation */ bool condition_launch_position_valid; /**< indicates a valid launch position */ bool condition_home_position_valid; /**< indicates a valid home position (a valid home position is not always a valid launch) */ bool condition_local_position_valid; -- cgit v1.2.3 From e92a0cd10dc20ced072c77a0183a6112179f4639 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 25 Jul 2014 02:14:35 +0400 Subject: UAVCAN update for #1229 (windoze) --- uavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uavcan b/uavcan index f51ee9cde..d84fc8a84 160000 --- a/uavcan +++ b/uavcan @@ -1 +1 @@ -Subproject commit f51ee9cdecd7841f6208bfb0b16228888daad663 +Subproject commit d84fc8a84678d93f97f93b240c81472797ca5889 -- cgit v1.2.3 From 8f0af1c5fe5a843c56fff2dc70acb2fc0e7e1b90 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 25 Jul 2014 00:16:02 +0200 Subject: mavlink: forwarding and FTP fixed, flow control detector fixed --- src/modules/mavlink/mavlink_main.cpp | 97 ++++++++++++++++++++++++------------ src/modules/mavlink/mavlink_main.h | 19 ++++--- 2 files changed, 77 insertions(+), 39 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index e27a940cf..aaee0455a 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -93,7 +93,7 @@ static const int ERROR = -1; #define MAX_DATA_RATE 10000 // max data rate in bytes/s #define MAIN_LOOP_DELAY 10000 // 100 Hz @ 1000 bytes/s data rate -#define TX_BUFFER_GAP 256 +#define TX_BUFFER_GAP MAVLINK_MAX_PACKET_LEN static Mavlink *_mavlink_instances = nullptr; @@ -252,25 +252,6 @@ Mavlink::count_txerr() perf_count(_txerr_perf); } -unsigned -Mavlink::get_free_tx_buf() -{ - unsigned buf_free; - - if (!ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free)) { - if (_rstatus.telem_time > 0 && - (hrt_elapsed_time(&_rstatus.telem_time) < (2 * 1000 * 1000))) { - - return (unsigned)(buf_free * 0.01f * _rstatus.txbuf); - - } else { - return buf_free; - } - } else { - return 0; - } -} - void Mavlink::set_mode(enum MAVLINK_MODE mode) { @@ -686,15 +667,9 @@ Mavlink::set_hil_enabled(bool hil_enabled) return ret; } -void -Mavlink::send_message(const uint8_t msgid, const void *msg) +unsigned +Mavlink::get_free_tx_buf() { - /* If the wait until transmit flag is on, only transmit after we've received messages. - Otherwise, transmit all the time. */ - if (!should_transmit()) { - return; - } - /* * Check if the OS buffer is full and disable HW * flow control if it continues to be full @@ -702,7 +677,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) int buf_free = 0; (void) ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free); - if (get_flow_control_enabled() && buf_free == 0) { + if (get_flow_control_enabled() && buf_free < TX_BUFFER_GAP) { /* Disable hardware flow control: * if no successful write since a defined time * and if the last try was not the last successful write @@ -714,6 +689,19 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) enable_flow_control(false); } } + return buf_free; +} + +void +Mavlink::send_message(const uint8_t msgid, const void *msg) +{ + /* If the wait until transmit flag is on, only transmit after we've received messages. + Otherwise, transmit all the time. */ + if (!should_transmit()) { + return; + } + + int buf_free = get_free_tx_buf(); uint8_t payload_len = mavlink_message_lengths[msgid]; unsigned packet_len = payload_len + MAVLINK_NUM_NON_PAYLOAD_BYTES; @@ -722,7 +710,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) /* check if there is space in the buffer, let it overflow else */ if (buf_free < TX_BUFFER_GAP) { - warnx("SKIP msgid %i, %i bytes", msgid, packet_len); + warnx("SKIP msgid %i, %i bytes, free %i", msgid, packet_len, buf_free); /* no enough space in buffer to send */ count_txerr(); count_txerrbytes(packet_len); @@ -764,6 +752,52 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) } } +void +Mavlink::resend_message(mavlink_message_t *msg) +{ + /* If the wait until transmit flag is on, only transmit after we've received messages. + Otherwise, transmit all the time. */ + if (!should_transmit()) { + return; + } + + int buf_free = get_free_tx_buf(); + + _last_write_try_time = hrt_absolute_time(); + + unsigned packet_len = msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES; + + /* check if there is space in the buffer, let it overflow else */ + if (buf_free < TX_BUFFER_GAP) { + warnx("SKIP resent msgid %i, %i bytes, free %i", msg->msgid, packet_len, buf_free); + /* no enough space in buffer to send */ + count_txerr(); + count_txerrbytes(packet_len); + return; + } + + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; + + /* header and payload */ + memcpy(&buf[0], &msg->magic, MAVLINK_NUM_HEADER_BYTES + msg->len); + + /* checksum */ + buf[MAVLINK_NUM_HEADER_BYTES + msg->len] = (uint8_t)(msg->checksum & 0xFF); + buf[MAVLINK_NUM_HEADER_BYTES + msg->len + 1] = (uint8_t)(msg->checksum >> 8); + + /* send message to UART */ + ssize_t ret = write(_uart_fd, buf, packet_len); + + if (ret != (int) packet_len) { + count_txerr(); + count_txerrbytes(packet_len); + + } else { + _last_write_success_time = _last_write_try_time; + count_txbytes(packet_len); + } +} + void Mavlink::handle_message(const mavlink_message_t *msg) { @@ -1411,8 +1445,7 @@ Mavlink::task_main(int argc, char *argv[]) pthread_mutex_unlock(&_message_buffer_mutex); - // TODO implement message resending - //_mavlink_resend_uart(_channel, &msg); + resend_message(&msg); } } diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index e3bad828f..4121e286e 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -162,6 +162,11 @@ public: void send_message(const uint8_t msgid, const void *msg); + /** + * Resend message as is, don't change sequence number and CRC. + */ + void resend_message(mavlink_message_t *msg); + void handle_message(const mavlink_message_t *msg); MavlinkOrbSubscription *add_orb_subscription(const orb_id_t topic); @@ -251,13 +256,6 @@ public: */ void count_rxbytes(unsigned n) { _bytes_rx += n; }; - /** - * Get the free space in the transmit buffer - * - * @return free space in the UART TX buffer - */ - unsigned get_free_tx_buf(); - /** * Get the receive status of this MAVLink link */ @@ -358,6 +356,13 @@ private: int mavlink_open_uart(int baudrate, const char *uart_name, struct termios *uart_config_original, bool *is_usb); + /** + * Get the free space in the transmit buffer + * + * @return free space in the UART TX buffer + */ + unsigned get_free_tx_buf(); + static unsigned int interval_from_rate(float rate); int configure_stream(const char *stream_name, const float rate); -- cgit v1.2.3 From 80a197f0fffb39037ce271bbc2e2107f2208eb01 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 25 Jul 2014 09:45:23 +0200 Subject: Revert "mavlink: use correct component ID" This reverts commit 36d8d73aeb7ef214979a64960df727bf3bab048c. --- src/modules/mavlink/mavlink_messages.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 92e469619..6885bebde 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1832,11 +1832,11 @@ protected: || status.arming_state == ARMING_STATE_ARMED_ERROR) { /* send camera capture on */ - mavlink_msg_command_long_send(_channel, mavlink_system.sysid, mavlink_system.compid, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0); + mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0); } else { /* send camera capture off */ - mavlink_msg_command_long_send(_channel, mavlink_system.sysid, mavlink_system.compid, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0); + mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0); } } }; -- cgit v1.2.3 From 1938ef16e39ff937a3076489f3eff0a2eb4bbb65 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 25 Jul 2014 14:27:07 +0200 Subject: mavlink: don't scale up rates, debug output removed --- src/modules/mavlink/mavlink_main.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index aaee0455a..572d5c19b 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -610,6 +610,9 @@ int Mavlink::mavlink_open_uart(int baud, const char *uart_name, struct termios * if (enable_flow_control(true)) { warnx("hardware flow control not supported"); } + + } else { + _flow_control_enabled = false; } return _uart_fd; @@ -651,8 +654,7 @@ Mavlink::set_hil_enabled(bool hil_enabled) /* enable HIL */ if (hil_enabled && !_hil_enabled) { _hil_enabled = true; - float rate_mult = _datarate / 1000.0f; - configure_stream("HIL_CONTROLS", 15.0f * rate_mult); + configure_stream("HIL_CONTROLS", 150.0f); } /* disable HIL */ @@ -710,7 +712,6 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) /* check if there is space in the buffer, let it overflow else */ if (buf_free < TX_BUFFER_GAP) { - warnx("SKIP msgid %i, %i bytes, free %i", msgid, packet_len, buf_free); /* no enough space in buffer to send */ count_txerr(); count_txerrbytes(packet_len); @@ -769,7 +770,6 @@ Mavlink::resend_message(mavlink_message_t *msg) /* check if there is space in the buffer, let it overflow else */ if (buf_free < TX_BUFFER_GAP) { - warnx("SKIP resent msgid %i, %i bytes, free %i", msg->msgid, packet_len, buf_free); /* no enough space in buffer to send */ count_txerr(); count_txerrbytes(packet_len); @@ -1120,7 +1120,8 @@ Mavlink::update_rate_mult() } } - _rate_mult = ((float)_datarate - const_rate) / rate; + /* don't scale up rates, only scale down if needed */ + _rate_mult = fminf(1.0f, ((float)_datarate - const_rate) / rate); } int @@ -1364,7 +1365,6 @@ Mavlink::task_main(int argc, char *argv[]) hrt_abstime t = hrt_absolute_time(); update_rate_mult(); - warnx("rate mult %.2f rate %.3f err %.3f", (double)_rate_mult, (double)_rate_tx, (double)_rate_txerr); if (param_sub->update(¶m_time, nullptr)) { /* parameters updated */ -- cgit v1.2.3 From 07c4144cde1026c4d966d043d12e36ba686c0781 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 25 Jul 2014 14:30:06 +0200 Subject: mavlink: message buffer size fixed --- src/modules/mavlink/mavlink_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 572d5c19b..408799be4 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1268,7 +1268,7 @@ Mavlink::task_main(int argc, char *argv[]) * make space for two messages plus off-by-one space as we use the empty element * marker ring buffer approach. */ - if (OK != message_buffer_init(2 * MAVLINK_MAX_PACKET_LEN + 2)) { + if (OK != message_buffer_init(2 * sizeof(mavlink_message_t) + 1)) { errx(1, "can't allocate message buffer, exiting"); } -- cgit v1.2.3 From c5a623e15892d63eb3571bc450edea368b2894db Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 25 Jul 2014 14:30:45 +0200 Subject: rcS: set rates for parameters and missions on USB connection --- ROMFS/px4fmu_common/init.d/rc.usb | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index 1f8d8b862..d31ef11cf 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -5,6 +5,10 @@ mavlink start -r 10000 -d /dev/ttyACM0 -x # Enable a number of interesting streams we want via USB +mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 200 +usleep 100000 +mavlink stream -d /dev/ttyACM0 -s MISSION_ITEM -r 50 +usleep 100000 mavlink stream -d /dev/ttyACM0 -s NAMED_VALUE_FLOAT -r 10 usleep 100000 mavlink stream -d /dev/ttyACM0 -s OPTICAL_FLOW -r 10 -- cgit v1.2.3 From 2de38d0628f3146caea28cd42b30840241269f41 Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Fri, 25 Jul 2014 23:30:37 -0400 Subject: Improve update performance and clean up compiler warnings in px4io driver - Fix compiler warnings in px4io_serial.cpp - Fix compiler warnings in px4io_uploader.cpp - Rename confusing overloaded send method with nearly identical parameters in px4io_uploader.cpp - Improve update performance by using maximum size programming buffer since we are no longer limited by stack size. --- src/drivers/px4io/px4io_serial.cpp | 8 +++++++- src/drivers/px4io/px4io_uploader.cpp | 32 +++++++++++++++++--------------- src/drivers/px4io/uploader.h | 8 ++++---- 3 files changed, 28 insertions(+), 20 deletions(-) diff --git a/src/drivers/px4io/px4io_serial.cpp b/src/drivers/px4io/px4io_serial.cpp index c39494fb0..d227e15d5 100644 --- a/src/drivers/px4io/px4io_serial.cpp +++ b/src/drivers/px4io/px4io_serial.cpp @@ -157,6 +157,10 @@ private: perf_counter_t _pc_idle; perf_counter_t _pc_badidle; + /* do not allow top copying this class */ + PX4IO_serial(PX4IO_serial &); + PX4IO_serial& operator = (const PX4IO_serial &); + }; IOPacket PX4IO_serial::_dma_buffer; @@ -173,7 +177,9 @@ PX4IO_serial::PX4IO_serial() : _tx_dma(nullptr), _rx_dma(nullptr), _rx_dma_status(_dma_status_inactive), - _pc_txns(perf_alloc(PC_ELAPSED, "io_txns ")), + _bus_semaphore(SEM_INITIALIZER(0)), + _completion_semaphore(SEM_INITIALIZER(0)), + _pc_txns(perf_alloc(PC_ELAPSED, "io_txns ")), _pc_dmasetup(perf_alloc(PC_ELAPSED, "io_dmasetup ")), _pc_retries(perf_alloc(PC_COUNT, "io_retries ")), _pc_timeouts(perf_alloc(PC_COUNT, "io_timeouts ")), diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp index bf6893a7e..986e39dc8 100644 --- a/src/drivers/px4io/px4io_uploader.cpp +++ b/src/drivers/px4io/px4io_uploader.cpp @@ -65,7 +65,8 @@ PX4IO_Uploader::PX4IO_Uploader() : _io_fd(-1), - _fw_fd(-1) + _fw_fd(-1), + bl_rev(0) { } @@ -245,7 +246,7 @@ PX4IO_Uploader::upload(const char *filenames[]) } int -PX4IO_Uploader::recv(uint8_t &c, unsigned timeout) +PX4IO_Uploader::recv_byte_with_timeout(uint8_t *c, unsigned timeout) { struct pollfd fds[1]; @@ -262,22 +263,23 @@ PX4IO_Uploader::recv(uint8_t &c, unsigned timeout) return -ETIMEDOUT; } - read(_io_fd, &c, 1); + read(_io_fd, c, 1); #ifdef UDEBUG - log("recv 0x%02x", c); + log("recv_bytes 0x%02x", c); #endif return OK; } int -PX4IO_Uploader::recv(uint8_t *p, unsigned count) +PX4IO_Uploader::recv_bytes(uint8_t *p, unsigned count) { - int ret; - while (count--) { - ret = recv(*p++, 5000); + int ret = OK; + while (count) { + ret = recv_byte_with_timeout(p++, 5000); if (ret != OK) break; + count--; } return ret; } @@ -289,10 +291,10 @@ PX4IO_Uploader::drain() int ret; do { - // the small recv timeout here is to allow for fast + // the small recv_bytes timeout here is to allow for fast // drain when rebooting the io board for a forced // update of the fw without using the safety switch - ret = recv(c, 40); + ret = recv_byte_with_timeout(&c, 40); #ifdef UDEBUG if (ret == OK) { @@ -331,12 +333,12 @@ PX4IO_Uploader::get_sync(unsigned timeout) uint8_t c[2]; int ret; - ret = recv(c[0], timeout); + ret = recv_byte_with_timeout(c, timeout); if (ret != OK) return ret; - ret = recv(c[1], timeout); + ret = recv_byte_with_timeout(c + 1, timeout); if (ret != OK) return ret; @@ -372,7 +374,7 @@ PX4IO_Uploader::get_info(int param, uint32_t &val) send(param); send(PROTO_EOC); - ret = recv((uint8_t *)&val, sizeof(val)); + ret = recv_bytes((uint8_t *)&val, sizeof(val)); if (ret != OK) return ret; @@ -513,7 +515,7 @@ PX4IO_Uploader::verify_rev2(size_t fw_size) for (ssize_t i = 0; i < count; i++) { uint8_t c; - ret = recv(c, 5000); + ret = recv_byte_with_timeout(&c, 5000); if (ret != OK) { log("%d: got %d waiting for bytes", sent + i, ret); @@ -600,7 +602,7 @@ PX4IO_Uploader::verify_rev3(size_t fw_size_local) send(PROTO_GET_CRC); send(PROTO_EOC); - ret = recv((uint8_t*)(&crc), sizeof(crc)); + ret = recv_bytes((uint8_t*)(&crc), sizeof(crc)); if (ret != OK) { log("did not receive CRC checksum"); diff --git a/src/drivers/px4io/uploader.h b/src/drivers/px4io/uploader.h index 3e2142cf2..e17523413 100644 --- a/src/drivers/px4io/uploader.h +++ b/src/drivers/px4io/uploader.h @@ -74,19 +74,19 @@ private: INFO_BOARD_REV = 3, /**< board revision */ INFO_FLASH_SIZE = 4, /**< max firmware size in bytes */ - PROG_MULTI_MAX = 60, /**< protocol max is 255, must be multiple of 4 */ + PROG_MULTI_MAX = 248, /**< protocol max is 255, must be multiple of 4 */ }; int _io_fd; int _fw_fd; - uint32_t bl_rev; /**< bootloader revision */ + uint32_t bl_rev; /**< bootloader revision */ void log(const char *fmt, ...); - int recv(uint8_t &c, unsigned timeout); - int recv(uint8_t *p, unsigned count); + int recv_byte_with_timeout(uint8_t *c, unsigned timeout); + int recv_bytes(uint8_t *p, unsigned count); void drain(); int send(uint8_t c); int send(uint8_t *p, unsigned count); -- cgit v1.2.3 From 3a4da7c5fa827970a86777ee6f4dc201246f0d0d Mon Sep 17 00:00:00 2001 From: Jean Cyr Date: Sat, 26 Jul 2014 09:05:44 -0400 Subject: Revert to original loop Original loop was correct, and slightly more efficient. Retain initialization of ret to handle the case where passed in count is 0. --- src/drivers/px4io/px4io_uploader.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/drivers/px4io/px4io_uploader.cpp b/src/drivers/px4io/px4io_uploader.cpp index 986e39dc8..fb16f891f 100644 --- a/src/drivers/px4io/px4io_uploader.cpp +++ b/src/drivers/px4io/px4io_uploader.cpp @@ -274,12 +274,11 @@ int PX4IO_Uploader::recv_bytes(uint8_t *p, unsigned count) { int ret = OK; - while (count) { + while (count--) { ret = recv_byte_with_timeout(p++, 5000); if (ret != OK) break; - count--; } return ret; } -- cgit v1.2.3 From 54b9698d6560290e386b8dd2a7b9f0b6f4c5f57a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 26 Jul 2014 17:48:45 +0200 Subject: circuit_breakers: added param to disable airspeed check --- src/modules/commander/commander.cpp | 2 ++ src/modules/commander/state_machine_helper.cpp | 4 +++- src/modules/systemlib/circuit_breaker.c | 12 ++++++++++++ src/modules/systemlib/circuit_breaker.h | 1 + src/modules/uORB/topics/vehicle_status.h | 1 + 5 files changed, 19 insertions(+), 1 deletion(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index a0c896178..daba4e740 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -736,6 +736,7 @@ int commander_thread_main(int argc, char *argv[]) // CIRCUIT BREAKERS status.circuit_breaker_engaged_power_check = false; + status.circuit_breaker_engaged_airspd_check = false; /* publish initial state */ status_pub = orb_advertise(ORB_ID(vehicle_status), &status); @@ -977,6 +978,7 @@ int commander_thread_main(int argc, char *argv[]) param_get(_param_component_id, &(status.component_id)); status.circuit_breaker_engaged_power_check = circuit_breaker_enabled("CBRK_SUPPLY_CHK", CBRK_SUPPLY_CHK_KEY); + status.circuit_breaker_engaged_airspd_check = circuit_breaker_enabled("CBRK_AIRSPD_CHK", CBRK_AIRSPD_CHK_KEY); status_changed = true; diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 7b26e3e8c..3c3d2f233 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -669,7 +669,9 @@ int prearm_check(const struct vehicle_status_s *status, const int mavlink_fd) goto system_eval; } - if (!status->is_rotary_wing) { + /* Perform airspeed check only if circuit breaker is not + * engaged and it's not a rotary wing */ + if (!status->circuit_breaker_engaged_airspd_check && !status->is_rotary_wing) { /* accel done, close it */ close(fd); fd = orb_subscribe(ORB_ID(airspeed)); diff --git a/src/modules/systemlib/circuit_breaker.c b/src/modules/systemlib/circuit_breaker.c index 8f697749e..64317a18a 100644 --- a/src/modules/systemlib/circuit_breaker.c +++ b/src/modules/systemlib/circuit_breaker.c @@ -83,6 +83,18 @@ PARAM_DEFINE_INT32(CBRK_RATE_CTRL, 0); */ PARAM_DEFINE_INT32(CBRK_IO_SAFETY, 0); +/** + * Circuit breaker for airspeed sensor + * + * Setting this parameter to 162128 will disable the check for an airspeed sensor. + * WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK + * + * @min 0 + * @max 162128 + * @group Circuit Breaker + */ +PARAM_DEFINE_INT32(CBRK_AIRSPD_CHK, 0); + bool circuit_breaker_enabled(const char* breaker, int32_t magic) { int32_t val; diff --git a/src/modules/systemlib/circuit_breaker.h b/src/modules/systemlib/circuit_breaker.h index 1175dbce8..b60584608 100644 --- a/src/modules/systemlib/circuit_breaker.h +++ b/src/modules/systemlib/circuit_breaker.h @@ -52,6 +52,7 @@ #define CBRK_SUPPLY_CHK_KEY 894281 #define CBRK_RATE_CTRL_KEY 140253 #define CBRK_IO_SAFETY_KEY 22027 +#define CBRK_AIRSPD_CHK_KEY 162128 #include diff --git a/src/modules/uORB/topics/vehicle_status.h b/src/modules/uORB/topics/vehicle_status.h index cbb148eda..b683bf98a 100644 --- a/src/modules/uORB/topics/vehicle_status.h +++ b/src/modules/uORB/topics/vehicle_status.h @@ -226,6 +226,7 @@ struct vehicle_status_s { uint16_t errors_count4; bool circuit_breaker_engaged_power_check; + bool circuit_breaker_engaged_airspd_check; }; /** -- cgit v1.2.3 From 5d36381dc5f3bbb1eefc70158680f9622ac437b6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 27 Jul 2014 23:38:14 +0200 Subject: EKF: Fix wind publication, fix commented out flags --- .../ekf_att_pos_estimator_main.cpp | 27 ++++------------------ 1 file changed, 4 insertions(+), 23 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp index ccc497323..91d17e787 100644 --- a/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp +++ b/src/modules/ekf_att_pos_estimator/ekf_att_pos_estimator_main.cpp @@ -630,10 +630,10 @@ FixedwingEstimator::check_filter_state() rep.health_flags |= (((uint8_t)ekf_report.posHealth) << 1); rep.health_flags |= (((uint8_t)ekf_report.hgtHealth) << 2); rep.health_flags |= (((uint8_t)!ekf_report.gyroOffsetsExcessive) << 3); - // rep.health_flags |= (((uint8_t)ekf_report.onGround) << 4); - // rep.health_flags |= (((uint8_t)ekf_report.staticMode) << 5); - // rep.health_flags |= (((uint8_t)ekf_report.useCompass) << 6); - // rep.health_flags |= (((uint8_t)ekf_report.useAirspeed) << 7); + rep.health_flags |= (((uint8_t)ekf_report.onGround) << 4); + rep.health_flags |= (((uint8_t)ekf_report.staticMode) << 5); + rep.health_flags |= (((uint8_t)ekf_report.useCompass) << 6); + rep.health_flags |= (((uint8_t)ekf_report.useAirspeed) << 7); rep.timeout_flags |= (((uint8_t)ekf_report.velTimeout) << 0); rep.timeout_flags |= (((uint8_t)ekf_report.posTimeout) << 1); @@ -1465,25 +1465,6 @@ FixedwingEstimator::task_main() _global_pos_pub = orb_advertise(ORB_ID(vehicle_global_position), &_global_pos); } - if (hrt_elapsed_time(&_wind.timestamp) > 99000) { - _wind.timestamp = _global_pos.timestamp; - _wind.windspeed_north = _ekf->states[14]; - _wind.windspeed_east = _ekf->states[15]; - _wind.covariance_north = 0.0f; // XXX get form filter - _wind.covariance_east = 0.0f; - - /* lazily publish the wind estimate only once available */ - if (_wind_pub > 0) { - /* publish the wind estimate */ - orb_publish(ORB_ID(wind_estimate), _wind_pub, &_wind); - - } else { - /* advertise and publish */ - _wind_pub = orb_advertise(ORB_ID(wind_estimate), &_wind); - } - - } - if (hrt_elapsed_time(&_wind.timestamp) > 99000) { _wind.timestamp = _global_pos.timestamp; _wind.windspeed_north = _ekf->states[14]; -- cgit v1.2.3 From 8e12d79ef4b32da98dfb13af1321a6855ecbdc3d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 27 Jul 2014 23:43:39 +0200 Subject: Increase GPS position timeout to real-life timeouts. More work needed. --- src/modules/commander/commander.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index daba4e740..6c24734e5 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -124,7 +124,7 @@ extern struct system_load_s system_load; #define STICK_ON_OFF_HYSTERESIS_TIME_MS 1000 #define STICK_ON_OFF_COUNTER_LIMIT (STICK_ON_OFF_HYSTERESIS_TIME_MS*COMMANDER_MONITORING_LOOPSPERMSEC) -#define POSITION_TIMEOUT (600 * 1000) /**< consider the local or global position estimate invalid after 600ms */ +#define POSITION_TIMEOUT (2 * 1000 * 1000) /**< consider the local or global position estimate invalid after 600ms */ #define FAILSAFE_DEFAULT_TIMEOUT (3 * 1000 * 1000) /**< hysteresis time - the failsafe will trigger after 3 seconds in this state */ #define RC_TIMEOUT 500000 #define DL_TIMEOUT 5 * 1000* 1000 @@ -1111,7 +1111,7 @@ int commander_thread_main(int argc, char *argv[]) bool eph_epv_good; if (status.condition_global_position_valid) { - if (global_position.eph > eph_epv_threshold * 2.0f || global_position.epv > eph_epv_threshold * 2.0f) { + if (global_position.eph > eph_epv_threshold * 2.5f || global_position.epv > eph_epv_threshold * 2.5f) { eph_epv_good = false; } else { -- cgit v1.2.3 From e1361fdc02a75d72849b52a0102e02e400eecd9e Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 28 Jul 2014 00:07:01 +0200 Subject: mavlink: GPS_RAW_INT stream added --- src/modules/mavlink/mavlink_messages.cpp | 134 ++++++++++++++++--------------- 1 file changed, 71 insertions(+), 63 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 4333369fe..8f0c15f5a 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -839,69 +839,77 @@ protected: }; -//class MavlinkStreamGPSRawInt : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamGPSRawInt::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "GPS_RAW_INT"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_GPS_RAW_INT; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamGPSRawInt(); -// } -// -//private: -// MavlinkOrbSubscription *gps_sub; -// uint64_t gps_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamGPSRawInt(MavlinkStreamGPSRawInt &); -// MavlinkStreamGPSRawInt& operator = (const MavlinkStreamGPSRawInt &); -// -//protected: -// explicit MavlinkStreamGPSRawInt() : MavlinkStream(), -// gps_sub(nullptr), -// gps_time(0) -// {} -// -// void subscribe() -// { -// gps_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_gps_position_s gps; -// -// if (gps_sub->update(&gps_time, &gps)) { -// mavlink_msg_gps_raw_int_send(_channel, -// gps.timestamp_position, -// gps.fix_type, -// gps.lat, -// gps.lon, -// gps.alt, -// cm_uint16_from_m_float(gps.eph), -// cm_uint16_from_m_float(gps.epv), -// gps.vel_m_s * 100.0f, -// _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f, -// gps.satellites_used); -// } -// } -//}; -// -// +class MavlinkStreamGPSRawInt : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamGPSRawInt::get_name_static(); + } + + static const char *get_name_static() + { + return "GPS_RAW_INT"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_GPS_RAW_INT; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamGPSRawInt(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_GPS_RAW_INT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_gps_sub; + uint64_t _gps_time; + + /* do not allow top copying this class */ + MavlinkStreamGPSRawInt(MavlinkStreamGPSRawInt &); + MavlinkStreamGPSRawInt& operator = (const MavlinkStreamGPSRawInt &); + +protected: + explicit MavlinkStreamGPSRawInt(Mavlink *mavlink) : MavlinkStream(mavlink), + _gps_sub(nullptr), + _gps_time(0) + {} + + void subscribe() + { + _gps_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position)); + } + + void send(const hrt_abstime t) + { + struct vehicle_gps_position_s gps; + + if (_gps_sub->update(&_gps_time, &gps)) { + mavlink_gps_raw_int_t msg; + + msg.time_usec = gps.timestamp_position; + msg.fix_type = gps.fix_type; + msg.lat = gps.lat; + msg.lon = gps.lon; + msg.alt = gps.alt; + msg.eph = cm_uint16_from_m_float(gps.eph); + msg.epv = cm_uint16_from_m_float(gps.epv); + msg.vel = cm_uint16_from_m_float(gps.vel_m_s), + msg.cog = _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f, + msg.satellites_visible = gps.satellites_used; + + _mavlink->send_message(MAVLINK_MSG_ID_GPS_RAW_INT, &msg); + } + } +}; + + //class MavlinkStreamGlobalPositionInt : public MavlinkStream //{ //public: -- cgit v1.2.3 From f1b55e578ff17d59cba13193cca4c83e764854b6 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 28 Jul 2014 11:02:56 +0200 Subject: mavlink: more streams ported to new API --- src/modules/mavlink/mavlink_messages.cpp | 713 ++++++++++++++++--------------- 1 file changed, 362 insertions(+), 351 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 8f0c15f5a..fe33c1bea 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -877,15 +877,10 @@ private: protected: explicit MavlinkStreamGPSRawInt(Mavlink *mavlink) : MavlinkStream(mavlink), - _gps_sub(nullptr), + _gps_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position))), _gps_time(0) {} - void subscribe() - { - _gps_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position)); - } - void send(const hrt_abstime t) { struct vehicle_gps_position_s gps; @@ -910,339 +905,355 @@ protected: }; -//class MavlinkStreamGlobalPositionInt : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamGlobalPositionInt::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "GLOBAL_POSITION_INT"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_GLOBAL_POSITION_INT; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamGlobalPositionInt(); -// } -// -//private: -// MavlinkOrbSubscription *pos_sub; -// uint64_t pos_time; -// -// MavlinkOrbSubscription *home_sub; -// uint64_t home_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamGlobalPositionInt(MavlinkStreamGlobalPositionInt &); -// MavlinkStreamGlobalPositionInt& operator = (const MavlinkStreamGlobalPositionInt &); -// -//protected: -// explicit MavlinkStreamGlobalPositionInt() : MavlinkStream(), -// pos_sub(nullptr), -// pos_time(0), -// home_sub(nullptr), -// home_time(0) -// {} -// -// void subscribe() -// { -// pos_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); -// home_sub = _mavlink->add_orb_subscription(ORB_ID(home_position)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_global_position_s pos; -// struct home_position_s home; -// -// bool updated = pos_sub->update(&pos_time, &pos); -// updated |= home_sub->update(&home_time, &home); -// -// if (updated) { -// mavlink_msg_global_position_int_send(_channel, -// pos.timestamp / 1000, -// pos.lat * 1e7, -// pos.lon * 1e7, -// pos.alt * 1000.0f, -// (pos.alt - home.alt) * 1000.0f, -// pos.vel_n * 100.0f, -// pos.vel_e * 100.0f, -// pos.vel_d * 100.0f, -// _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f); -// } -// } -//}; -// -// -//class MavlinkStreamLocalPositionNED : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamLocalPositionNED::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "LOCAL_POSITION_NED"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_LOCAL_POSITION_NED; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamLocalPositionNED(); -// } -// -//private: -// MavlinkOrbSubscription *pos_sub; -// uint64_t pos_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamLocalPositionNED(MavlinkStreamLocalPositionNED &); -// MavlinkStreamLocalPositionNED& operator = (const MavlinkStreamLocalPositionNED &); -// -//protected: -// explicit MavlinkStreamLocalPositionNED() : MavlinkStream(), -// pos_sub(nullptr), -// pos_time(0) -// {} -// -// void subscribe() -// { -// pos_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_local_position)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_local_position_s pos; -// -// if (pos_sub->update(&pos_time, &pos)) { -// mavlink_msg_local_position_ned_send(_channel, -// pos.timestamp / 1000, -// pos.x, -// pos.y, -// pos.z, -// pos.vx, -// pos.vy, -// pos.vz); -// } -// } -//}; -// -// -// -//class MavlinkStreamViconPositionEstimate : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamViconPositionEstimate::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "VICON_POSITION_ESTIMATE"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamViconPositionEstimate(); -// } -// -//private: -// MavlinkOrbSubscription *pos_sub; -// uint64_t pos_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamViconPositionEstimate(MavlinkStreamViconPositionEstimate &); -// MavlinkStreamViconPositionEstimate& operator = (const MavlinkStreamViconPositionEstimate &); -// -//protected: -// explicit MavlinkStreamViconPositionEstimate() : MavlinkStream(), -// pos_sub(nullptr), -// pos_time(0) -// {} -// -// void subscribe() -// { -// pos_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_vicon_position_s pos; -// -// if (pos_sub->update(&pos_time, &pos)) { -// mavlink_msg_vicon_position_estimate_send(_channel, -// pos.timestamp / 1000, -// pos.x, -// pos.y, -// pos.z, -// pos.roll, -// pos.pitch, -// pos.yaw); -// } -// } -//}; -// -// -//class MavlinkStreamGPSGlobalOrigin : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamGPSGlobalOrigin::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "GPS_GLOBAL_ORIGIN"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamGPSGlobalOrigin(); -// } -// -//private: -// MavlinkOrbSubscription *home_sub; -// -// /* do not allow top copying this class */ -// MavlinkStreamGPSGlobalOrigin(MavlinkStreamGPSGlobalOrigin &); -// MavlinkStreamGPSGlobalOrigin& operator = (const MavlinkStreamGPSGlobalOrigin &); -// -//protected: -// explicit MavlinkStreamGPSGlobalOrigin() : MavlinkStream(), -// home_sub(nullptr) -// {} -// -// void subscribe() -// { -// home_sub = _mavlink->add_orb_subscription(ORB_ID(home_position)); -// } -// -// void send(const hrt_abstime t) -// { -// /* we're sending the GPS home periodically to ensure the -// * the GCS does pick it up at one point */ -// if (home_sub->is_published()) { -// struct home_position_s home; -// -// if (home_sub->update(&home)) { -// mavlink_msg_gps_global_origin_send(_channel, -// (int32_t)(home.lat * 1e7), -// (int32_t)(home.lon * 1e7), -// (int32_t)(home.alt) * 1000.0f); -// } -// } -// } -//}; -// -//template -//class MavlinkStreamServoOutputRaw : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamServoOutputRaw::get_name_static(); -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; -// } -// -// static const char *get_name_static() -// { -// switch (N) { -// case 0: -// return "SERVO_OUTPUT_RAW_0"; -// -// case 1: -// return "SERVO_OUTPUT_RAW_1"; -// -// case 2: -// return "SERVO_OUTPUT_RAW_2"; -// -// case 3: -// return "SERVO_OUTPUT_RAW_3"; -// } -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamServoOutputRaw(); -// } -// -//private: -// MavlinkOrbSubscription *act_sub; -// uint64_t act_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamServoOutputRaw(MavlinkStreamServoOutputRaw &); -// MavlinkStreamServoOutputRaw& operator = (const MavlinkStreamServoOutputRaw &); -// -//protected: -// explicit MavlinkStreamServoOutputRaw() : MavlinkStream(), -// act_sub(nullptr), -// act_time(0) -// {} -// -// void subscribe() -// { -// orb_id_t act_topics[] = { -// ORB_ID(actuator_outputs_0), -// ORB_ID(actuator_outputs_1), -// ORB_ID(actuator_outputs_2), -// ORB_ID(actuator_outputs_3) -// }; -// -// act_sub = _mavlink->add_orb_subscription(act_topics[N]); -// } -// -// void send(const hrt_abstime t) -// { -// struct actuator_outputs_s act; -// -// if (act_sub->update(&act_time, &act)) { -// mavlink_msg_servo_output_raw_send(_channel, -// act.timestamp / 1000, -// N, -// act.output[0], -// act.output[1], -// act.output[2], -// act.output[3], -// act.output[4], -// act.output[5], -// act.output[6], -// act.output[7]); -// } -// } -//}; -// -// +class MavlinkStreamGlobalPositionInt : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamGlobalPositionInt::get_name_static(); + } + + static const char *get_name_static() + { + return "GLOBAL_POSITION_INT"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_GLOBAL_POSITION_INT; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamGlobalPositionInt(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_pos_sub; + uint64_t _pos_time; + + MavlinkOrbSubscription *_home_sub; + uint64_t _home_time; + + /* do not allow top copying this class */ + MavlinkStreamGlobalPositionInt(MavlinkStreamGlobalPositionInt &); + MavlinkStreamGlobalPositionInt& operator = (const MavlinkStreamGlobalPositionInt &); + +protected: + explicit MavlinkStreamGlobalPositionInt(Mavlink *mavlink) : MavlinkStream(mavlink), + _pos_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_global_position))), + _pos_time(0), + _home_sub(_mavlink->add_orb_subscription(ORB_ID(home_position))), + _home_time(0) + {} + + void send(const hrt_abstime t) + { + struct vehicle_global_position_s pos; + struct home_position_s home; + + bool updated = _pos_sub->update(&_pos_time, &pos); + updated |= _home_sub->update(&_home_time, &home); + + if (updated) { + mavlink_global_position_int_t msg; + + msg.time_boot_ms = pos.timestamp / 1000; + msg.lat = pos.lat * 1e7; + msg.lon = pos.lon * 1e7; + msg.alt = pos.alt * 1000.0f; + msg.relative_alt = (pos.alt - home.alt) * 1000.0f; + msg.vx = pos.vel_n * 100.0f; + msg.vy = pos.vel_e * 100.0f; + msg.vz = pos.vel_d * 100.0f; + msg.hdg = _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f; + + _mavlink->send_message(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, &msg); + } + } +}; + + +class MavlinkStreamLocalPositionNED : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamLocalPositionNED::get_name_static(); + } + + static const char *get_name_static() + { + return "LOCAL_POSITION_NED"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_LOCAL_POSITION_NED; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamLocalPositionNED(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_pos_sub; + uint64_t _pos_time; + + /* do not allow top copying this class */ + MavlinkStreamLocalPositionNED(MavlinkStreamLocalPositionNED &); + MavlinkStreamLocalPositionNED& operator = (const MavlinkStreamLocalPositionNED &); + +protected: + explicit MavlinkStreamLocalPositionNED(Mavlink *mavlink) : MavlinkStream(mavlink), + _pos_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_local_position))), + _pos_time(0) + {} + + void send(const hrt_abstime t) + { + struct vehicle_local_position_s pos; + + if (_pos_sub->update(&_pos_time, &pos)) { + mavlink_local_position_ned_t msg; + + msg.time_boot_ms = pos.timestamp / 1000; + msg.x = pos.x; + msg.y = pos.y; + msg.z = pos.z; + msg.vx = pos.vx; + msg.vy = pos.vy; + msg.vz = pos.vz; + + _mavlink->send_message(MAVLINK_MSG_ID_LOCAL_POSITION_NED, &msg); + } + } +}; + + +class MavlinkStreamViconPositionEstimate : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamViconPositionEstimate::get_name_static(); + } + + static const char *get_name_static() + { + return "VICON_POSITION_ESTIMATE"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamViconPositionEstimate(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_pos_sub; + uint64_t _pos_time; + + /* do not allow top copying this class */ + MavlinkStreamViconPositionEstimate(MavlinkStreamViconPositionEstimate &); + MavlinkStreamViconPositionEstimate& operator = (const MavlinkStreamViconPositionEstimate &); + +protected: + explicit MavlinkStreamViconPositionEstimate(Mavlink *mavlink) : MavlinkStream(mavlink), + _pos_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position))), + _pos_time(0) + {} + + void send(const hrt_abstime t) + { + struct vehicle_vicon_position_s pos; + + if (_pos_sub->update(&_pos_time, &pos)) { + mavlink_vicon_position_estimate_t msg; + + msg.usec = pos.timestamp; + msg.x = pos.x; + msg.y = pos.y; + msg.z = pos.z; + msg.roll = pos.roll; + msg.pitch = pos.pitch; + msg.yaw = pos.yaw; + + _mavlink->send_message(MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, &msg); + } + } +}; + + +class MavlinkStreamGPSGlobalOrigin : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamGPSGlobalOrigin::get_name_static(); + } + + static const char *get_name_static() + { + return "GPS_GLOBAL_ORIGIN"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamGPSGlobalOrigin(mavlink); + } + + unsigned get_size() + { + return _home_sub->is_published() ? (MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0; + } + +private: + MavlinkOrbSubscription *_home_sub; + + /* do not allow top copying this class */ + MavlinkStreamGPSGlobalOrigin(MavlinkStreamGPSGlobalOrigin &); + MavlinkStreamGPSGlobalOrigin& operator = (const MavlinkStreamGPSGlobalOrigin &); + +protected: + explicit MavlinkStreamGPSGlobalOrigin(Mavlink *mavlink) : MavlinkStream(mavlink), + _home_sub(_mavlink->add_orb_subscription(ORB_ID(home_position))) + {} + + void send(const hrt_abstime t) + { + /* we're sending the GPS home periodically to ensure the + * the GCS does pick it up at one point */ + if (_home_sub->is_published()) { + struct home_position_s home; + + if (_home_sub->update(&home)) { + mavlink_gps_global_origin_t msg; + + msg.latitude = home.lat * 1e7; + msg.longitude = home.lon * 1e7; + msg.altitude = home.alt * 1e3f; + + _mavlink->send_message(MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, &msg); + } + } + } +}; + + +template +class MavlinkStreamServoOutputRaw : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamServoOutputRaw::get_name_static(); + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_SERVO_OUTPUT_RAW; + } + + static const char *get_name_static() + { + switch (N) { + case 0: + return "SERVO_OUTPUT_RAW_0"; + + case 1: + return "SERVO_OUTPUT_RAW_1"; + + case 2: + return "SERVO_OUTPUT_RAW_2"; + + case 3: + return "SERVO_OUTPUT_RAW_3"; + } + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamServoOutputRaw(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_act_sub; + uint64_t _act_time; + + /* do not allow top copying this class */ + MavlinkStreamServoOutputRaw(MavlinkStreamServoOutputRaw &); + MavlinkStreamServoOutputRaw& operator = (const MavlinkStreamServoOutputRaw &); + +protected: + explicit MavlinkStreamServoOutputRaw(Mavlink *mavlink) : MavlinkStream(mavlink), + _act_sub(nullptr), + _act_time(0) + { + orb_id_t act_topics[] = { + ORB_ID(actuator_outputs_0), + ORB_ID(actuator_outputs_1), + ORB_ID(actuator_outputs_2), + ORB_ID(actuator_outputs_3) + }; + + _act_sub = _mavlink->add_orb_subscription(act_topics[N]); + } + + void send(const hrt_abstime t) + { + struct actuator_outputs_s act; + + if (_act_sub->update(&_act_time, &act)) { + mavlink_servo_output_raw_t msg; + + msg.time_usec = act.timestamp; + msg.port = N; + msg.servo1_raw = act.output[0]; + msg.servo2_raw = act.output[1]; + msg.servo3_raw = act.output[2]; + msg.servo4_raw = act.output[3]; + msg.servo5_raw = act.output[4]; + msg.servo6_raw = act.output[5]; + msg.servo7_raw = act.output[6]; + msg.servo8_raw = act.output[7]; + + _mavlink->send_message(MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, &msg); + } + } +}; + + //class MavlinkStreamHILControls : public MavlinkStream //{ //public: @@ -1281,7 +1292,7 @@ protected: // MavlinkStreamHILControls& operator = (const MavlinkStreamHILControls &); // //protected: -// explicit MavlinkStreamHILControls() : MavlinkStream(), +// explicit MavlinkStreamHILControls() : MavlinkStream(mavlink), // status_sub(nullptr), // status_time(0), // pos_sp_triplet_sub(nullptr), @@ -1414,7 +1425,7 @@ protected: // MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &); // //protected: -// explicit MavlinkStreamGlobalPositionSetpointInt() : MavlinkStream(), +// explicit MavlinkStreamGlobalPositionSetpointInt() : MavlinkStream(mavlink), // pos_sp_triplet_sub(nullptr) // {} // @@ -1471,7 +1482,7 @@ protected: // MavlinkStreamLocalPositionSetpoint& operator = (const MavlinkStreamLocalPositionSetpoint &); // //protected: -// explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(), +// explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(mavlink), // pos_sp_sub(nullptr), // pos_sp_time(0) // {} @@ -1529,7 +1540,7 @@ protected: // MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &); // //protected: -// explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(), +// explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(mavlink), // att_sp_sub(nullptr), // att_sp_time(0) // {} @@ -1587,7 +1598,7 @@ protected: // MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &); // //protected: -// explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(), +// explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(mavlink), // att_rates_sp_sub(nullptr), // att_rates_sp_time(0) // {} @@ -1645,7 +1656,7 @@ protected: // MavlinkStreamRCChannelsRaw& operator = (const MavlinkStreamRCChannelsRaw &); // //protected: -// explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(), +// explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(mavlink), // rc_sub(nullptr), // rc_time(0) // {} @@ -1739,7 +1750,7 @@ protected: // MavlinkStreamManualControl& operator = (const MavlinkStreamManualControl &); // //protected: -// explicit MavlinkStreamManualControl() : MavlinkStream(), +// explicit MavlinkStreamManualControl() : MavlinkStream(mavlink), // manual_sub(nullptr), // manual_time(0) // {} @@ -1798,7 +1809,7 @@ protected: // MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &); // //protected: -// explicit MavlinkStreamOpticalFlow() : MavlinkStream(), +// explicit MavlinkStreamOpticalFlow() : MavlinkStream(mavlink), // flow_sub(nullptr), // flow_time(0) // {} @@ -1856,7 +1867,7 @@ protected: // MavlinkStreamAttitudeControls& operator = (const MavlinkStreamAttitudeControls &); // //protected: -// explicit MavlinkStreamAttitudeControls() : MavlinkStream(), +// explicit MavlinkStreamAttitudeControls() : MavlinkStream(mavlink), // att_ctrl_sub(nullptr), // att_ctrl_time(0) // {} @@ -1924,7 +1935,7 @@ protected: // MavlinkStreamNamedValueFloat& operator = (const MavlinkStreamNamedValueFloat &); // //protected: -// explicit MavlinkStreamNamedValueFloat() : MavlinkStream(), +// explicit MavlinkStreamNamedValueFloat() : MavlinkStream(mavlink), // debug_sub(nullptr), // debug_time(0) // {} @@ -1981,7 +1992,7 @@ protected: // MavlinkStreamCameraCapture& operator = (const MavlinkStreamCameraCapture &); // //protected: -// explicit MavlinkStreamCameraCapture() : MavlinkStream(), +// explicit MavlinkStreamCameraCapture() : MavlinkStream(mavlink), // status_sub(nullptr) // {} // @@ -2040,7 +2051,7 @@ protected: // MavlinkStreamDistanceSensor& operator = (const MavlinkStreamDistanceSensor &); // //protected: -// explicit MavlinkStreamDistanceSensor() : MavlinkStream(), +// explicit MavlinkStreamDistanceSensor() : MavlinkStream(mavlink), // range_sub(nullptr), // range_time(0) // {} -- cgit v1.2.3 From e087ec81c396d7da8d5f7a006748062ee07b693f Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 28 Jul 2014 13:53:45 +0200 Subject: mavlink: more streams ported to new API --- src/modules/mavlink/mavlink_messages.cpp | 522 ++++++++++++++++--------------- 1 file changed, 268 insertions(+), 254 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index fe33c1bea..14195b6a7 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1254,260 +1254,274 @@ protected: }; -//class MavlinkStreamHILControls : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamHILControls::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "HIL_CONTROLS"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_HIL_CONTROLS; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamHILControls(); -// } -// -//private: -// MavlinkOrbSubscription *status_sub; -// uint64_t status_time; -// -// MavlinkOrbSubscription *pos_sp_triplet_sub; -// uint64_t pos_sp_triplet_time; -// -// MavlinkOrbSubscription *act_sub; -// uint64_t act_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamHILControls(MavlinkStreamHILControls &); -// MavlinkStreamHILControls& operator = (const MavlinkStreamHILControls &); -// -//protected: -// explicit MavlinkStreamHILControls() : MavlinkStream(mavlink), -// status_sub(nullptr), -// status_time(0), -// pos_sp_triplet_sub(nullptr), -// pos_sp_triplet_time(0), -// act_sub(nullptr), -// act_time(0) -// {} -// -// void subscribe() -// { -// status_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); -// pos_sp_triplet_sub = _mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); -// act_sub = _mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_status_s status; -// struct position_setpoint_triplet_s pos_sp_triplet; -// struct actuator_outputs_s act; -// -// bool updated = act_sub->update(&act_time, &act); -// updated |= pos_sp_triplet_sub->update(&pos_sp_triplet_time, &pos_sp_triplet); -// updated |= status_sub->update(&status_time, &status); -// -// if (updated && (status.arming_state == ARMING_STATE_ARMED)) { -// /* translate the current syste state to mavlink state and mode */ -// uint8_t mavlink_state; -// uint8_t mavlink_base_mode; -// uint32_t mavlink_custom_mode; -// get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode); -// -// float out[8]; -// -// const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2; -// -// /* scale outputs depending on system type */ -// if (mavlink_system.type == MAV_TYPE_QUADROTOR || -// mavlink_system.type == MAV_TYPE_HEXAROTOR || -// mavlink_system.type == MAV_TYPE_OCTOROTOR) { -// /* multirotors: set number of rotor outputs depending on type */ -// -// unsigned n; -// -// switch (mavlink_system.type) { -// case MAV_TYPE_QUADROTOR: -// n = 4; -// break; -// -// case MAV_TYPE_HEXAROTOR: -// n = 6; -// break; -// -// default: -// n = 8; -// break; -// } -// -// for (unsigned i = 0; i < 8; i++) { -// if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) { -// if (i < n) { -// /* scale PWM out 900..2100 us to 0..1 for rotors */ -// out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); -// -// } else { -// /* scale PWM out 900..2100 us to -1..1 for other channels */ -// out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); -// } -// -// } else { -// /* send 0 when disarmed */ -// out[i] = 0.0f; -// } -// } -// -// } else { -// /* fixed wing: scale throttle to 0..1 and other channels to -1..1 */ -// -// for (unsigned i = 0; i < 8; i++) { -// if (i != 3) { -// /* scale PWM out 900..2100 us to -1..1 for normal channels */ -// out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); -// -// } else { -// /* scale PWM out 900..2100 us to 0..1 for throttle */ -// out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); -// } -// -// } -// } -// -// mavlink_msg_hil_controls_send(_channel, -// hrt_absolute_time(), -// out[0], out[1], out[2], out[3], out[4], out[5], out[6], out[7], -// mavlink_base_mode, -// 0); -// } -// } -//}; -// -// -//class MavlinkStreamGlobalPositionSetpointInt : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamGlobalPositionSetpointInt::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "GLOBAL_POSITION_SETPOINT_INT"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamGlobalPositionSetpointInt(); -// } -// -//private: -// MavlinkOrbSubscription *pos_sp_triplet_sub; -// -// /* do not allow top copying this class */ -// MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &); -// MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &); -// -//protected: -// explicit MavlinkStreamGlobalPositionSetpointInt() : MavlinkStream(mavlink), -// pos_sp_triplet_sub(nullptr) -// {} -// -// void subscribe() -// { -// pos_sp_triplet_sub = _mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); -// } -// -// void send(const hrt_abstime t) -// { -// struct position_setpoint_triplet_s pos_sp_triplet; -// -// if (pos_sp_triplet_sub->update(&pos_sp_triplet)) { -// mavlink_msg_global_position_setpoint_int_send(_channel, -// MAV_FRAME_GLOBAL, -// (int32_t)(pos_sp_triplet.current.lat * 1e7), -// (int32_t)(pos_sp_triplet.current.lon * 1e7), -// (int32_t)(pos_sp_triplet.current.alt * 1000), -// (int16_t)(pos_sp_triplet.current.yaw * M_RAD_TO_DEG_F * 100.0f)); -// } -// } -//}; -// -// -//class MavlinkStreamLocalPositionSetpoint : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamLocalPositionSetpoint::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "LOCAL_POSITION_SETPOINT"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamLocalPositionSetpoint(); -// } -// -//private: -// MavlinkOrbSubscription *pos_sp_sub; -// uint64_t pos_sp_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamLocalPositionSetpoint(MavlinkStreamLocalPositionSetpoint &); -// MavlinkStreamLocalPositionSetpoint& operator = (const MavlinkStreamLocalPositionSetpoint &); -// -//protected: -// explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(mavlink), -// pos_sp_sub(nullptr), -// pos_sp_time(0) -// {} -// -// void subscribe() -// { -// pos_sp_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_local_position_setpoint_s pos_sp; -// -// if (pos_sp_sub->update(&pos_sp_time, &pos_sp)) { -// mavlink_msg_local_position_setpoint_send(_channel, -// MAV_FRAME_LOCAL_NED, -// pos_sp.x, -// pos_sp.y, -// pos_sp.z, -// pos_sp.yaw); -// } -// } -//}; -// -// +class MavlinkStreamHILControls : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamHILControls::get_name_static(); + } + + static const char *get_name_static() + { + return "HIL_CONTROLS"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_HIL_CONTROLS; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamHILControls(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_HIL_CONTROLS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_status_sub; + uint64_t _status_time; + + MavlinkOrbSubscription *_pos_sp_triplet_sub; + uint64_t _pos_sp_triplet_time; + + MavlinkOrbSubscription *_act_sub; + uint64_t _act_time; + + /* do not allow top copying this class */ + MavlinkStreamHILControls(MavlinkStreamHILControls &); + MavlinkStreamHILControls& operator = (const MavlinkStreamHILControls &); + +protected: + explicit MavlinkStreamHILControls(Mavlink *mavlink) : MavlinkStream(mavlink), + _status_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_status))), + _status_time(0), + _pos_sp_triplet_sub(_mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet))), + _pos_sp_triplet_time(0), + _act_sub(_mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0))), + _act_time(0) + {} + + void send(const hrt_abstime t) + { + struct vehicle_status_s status; + struct position_setpoint_triplet_s pos_sp_triplet; + struct actuator_outputs_s act; + + bool updated = _act_sub->update(&_act_time, &act); + updated |= _pos_sp_triplet_sub->update(&_pos_sp_triplet_time, &pos_sp_triplet); + updated |= _status_sub->update(&_status_time, &status); + + if (updated && (status.arming_state == ARMING_STATE_ARMED)) { + /* translate the current syste state to mavlink state and mode */ + uint8_t mavlink_state; + uint8_t mavlink_base_mode; + uint32_t mavlink_custom_mode; + get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode); + + float out[8]; + + const float pwm_center = (PWM_HIGHEST_MAX + PWM_LOWEST_MIN) / 2; + + /* scale outputs depending on system type */ + if (mavlink_system.type == MAV_TYPE_QUADROTOR || + mavlink_system.type == MAV_TYPE_HEXAROTOR || + mavlink_system.type == MAV_TYPE_OCTOROTOR) { + /* multirotors: set number of rotor outputs depending on type */ + + unsigned n; + + switch (mavlink_system.type) { + case MAV_TYPE_QUADROTOR: + n = 4; + break; + + case MAV_TYPE_HEXAROTOR: + n = 6; + break; + + default: + n = 8; + break; + } + + for (unsigned i = 0; i < 8; i++) { + if (mavlink_base_mode & MAV_MODE_FLAG_SAFETY_ARMED) { + if (i < n) { + /* scale PWM out 900..2100 us to 0..1 for rotors */ + out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); + + } else { + /* scale PWM out 900..2100 us to -1..1 for other channels */ + out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); + } + + } else { + /* send 0 when disarmed */ + out[i] = 0.0f; + } + } + + } else { + /* fixed wing: scale throttle to 0..1 and other channels to -1..1 */ + + for (unsigned i = 0; i < 8; i++) { + if (i != 3) { + /* scale PWM out 900..2100 us to -1..1 for normal channels */ + out[i] = (act.output[i] - pwm_center) / ((PWM_HIGHEST_MAX - PWM_LOWEST_MIN) / 2); + + } else { + /* scale PWM out 900..2100 us to 0..1 for throttle */ + out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); + } + + } + } + + mavlink_hil_controls_t msg; + + msg.time_usec = hrt_absolute_time(); + msg.roll_ailerons = out[0]; + msg.pitch_elevator = out[1]; + msg.yaw_rudder = out[2]; + msg.throttle = out[3]; + msg.aux1 = out[4]; + msg.aux2 = out[5]; + msg.aux3 = out[6]; + msg.aux4 = out[7]; + msg.mode = mavlink_base_mode; + msg.nav_mode = 0; + + _mavlink->send_message(MAVLINK_MSG_ID_HIL_CONTROLS, &msg); + } + } +}; + + +class MavlinkStreamGlobalPositionSetpointInt : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamGlobalPositionSetpointInt::get_name_static(); + } + + static const char *get_name_static() + { + return "GLOBAL_POSITION_SETPOINT_INT"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamGlobalPositionSetpointInt(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_pos_sp_triplet_sub; + + /* do not allow top copying this class */ + MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &); + MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &); + +protected: + explicit MavlinkStreamGlobalPositionSetpointInt(Mavlink *mavlink) : MavlinkStream(mavlink), + _pos_sp_triplet_sub(_mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet))) + {} + + void send(const hrt_abstime t) + { + struct position_setpoint_triplet_s pos_sp_triplet; + + if (_pos_sp_triplet_sub->update(&pos_sp_triplet)) { + mavlink_global_position_setpoint_int_t msg; + + msg.coordinate_frame = MAV_FRAME_GLOBAL; + msg.latitude = pos_sp_triplet.current.lat * 1e7; + msg.longitude = pos_sp_triplet.current.lon * 1e7; + msg.altitude = pos_sp_triplet.current.alt * 1000; + msg.yaw = pos_sp_triplet.current.yaw * M_RAD_TO_DEG_F * 100.0f; + + _mavlink->send_message(MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, &msg); + } + } +}; + + +class MavlinkStreamLocalPositionSetpoint : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamLocalPositionSetpoint::get_name_static(); + } + + static const char *get_name_static() + { + return "LOCAL_POSITION_SETPOINT"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamLocalPositionSetpoint(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_pos_sp_sub; + uint64_t _pos_sp_time; + + /* do not allow top copying this class */ + MavlinkStreamLocalPositionSetpoint(MavlinkStreamLocalPositionSetpoint &); + MavlinkStreamLocalPositionSetpoint& operator = (const MavlinkStreamLocalPositionSetpoint &); + +protected: + explicit MavlinkStreamLocalPositionSetpoint(Mavlink *mavlink) : MavlinkStream(mavlink), + _pos_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint))), + _pos_sp_time(0) + {} + + void send(const hrt_abstime t) + { + struct vehicle_local_position_setpoint_s pos_sp; + + if (_pos_sp_sub->update(&_pos_sp_time, &pos_sp)) { + mavlink_local_position_setpoint_t msg; + + msg.coordinate_frame = MAV_FRAME_LOCAL_NED; + msg.x = pos_sp.x; + msg.y = pos_sp.y; + msg.z = pos_sp.z; + msg.yaw = pos_sp.yaw; + + _mavlink->send_message(MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, &msg); + } + } +}; + + //class MavlinkStreamRollPitchYawThrustSetpoint : public MavlinkStream //{ //public: -- cgit v1.2.3 From 3b3e6f5aaafd1247447cad7070e3488e5798ce3c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 28 Jul 2014 14:21:50 +0200 Subject: Increase filter pass-band --- src/drivers/meas_airspeed/meas_airspeed.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 118c35960..03e50e5cb 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -103,7 +103,7 @@ /* Measurement rate is 100Hz */ #define MEAS_RATE 100 -#define MEAS_DRIVER_FILTER_FREQ 0.5f +#define MEAS_DRIVER_FILTER_FREQ 0.8f #define CONVERSION_INTERVAL (1000000 / MEAS_RATE) /* microseconds */ class MEASAirspeed : public Airspeed -- cgit v1.2.3 From 67db8ee4f0908c31f17ed490c48ea21cc7ac3f86 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 28 Jul 2014 14:27:10 +0200 Subject: Add missing states, build fix for master --- src/modules/ekf_att_pos_estimator/estimator_23states.cpp | 4 ++++ src/modules/ekf_att_pos_estimator/estimator_utilities.h | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index 3d504d395..ffdd29a5b 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -3028,6 +3028,10 @@ void AttPosEKF::GetFilterState(struct ekf_status_report *err) current_ekf_state.states[i] = states[i]; } current_ekf_state.n_states = n_states; + current_ekf_state.onGround = onGround; + current_ekf_state.staticMode = staticMode; + current_ekf_state.useCompass = useCompass; + current_ekf_state.useAirspeed = useAirspeed; memcpy(err, ¤t_ekf_state, sizeof(*err)); diff --git a/src/modules/ekf_att_pos_estimator/estimator_utilities.h b/src/modules/ekf_att_pos_estimator/estimator_utilities.h index 6d1f47b68..a6b670c4d 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_utilities.h +++ b/src/modules/ekf_att_pos_estimator/estimator_utilities.h @@ -68,6 +68,10 @@ struct ekf_status_report { bool posTimeout; bool hgtTimeout; bool imuTimeout; + bool onGround; + bool staticMode; + bool useCompass; + bool useAirspeed; uint32_t velFailTime; uint32_t posFailTime; uint32_t hgtFailTime; -- cgit v1.2.3 From 241802a71f2af56a8dd4510827f8ab5a59f5d6b9 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 28 Jul 2014 17:40:53 +0200 Subject: mavlink: more streams ported to new API --- src/modules/mavlink/mavlink_messages.cpp | 584 ++++++++++++++++--------------- 1 file changed, 300 insertions(+), 284 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 14195b6a7..a710cdf6a 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1522,275 +1522,291 @@ protected: }; -//class MavlinkStreamRollPitchYawThrustSetpoint : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamRollPitchYawThrustSetpoint::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "ROLL_PITCH_YAW_THRUST_SETPOINT"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamRollPitchYawThrustSetpoint(); -// } -// -//private: -// MavlinkOrbSubscription *att_sp_sub; -// uint64_t att_sp_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &); -// MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &); -// -//protected: -// explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(mavlink), -// att_sp_sub(nullptr), -// att_sp_time(0) -// {} -// -// void subscribe() -// { -// att_sp_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_attitude_setpoint_s att_sp; -// -// if (att_sp_sub->update(&att_sp_time, &att_sp)) { -// mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(_channel, -// att_sp.timestamp / 1000, -// att_sp.roll_body, -// att_sp.pitch_body, -// att_sp.yaw_body, -// att_sp.thrust); -// } -// } -//}; -// -// -//class MavlinkStreamRollPitchYawRatesThrustSetpoint : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamRollPitchYawRatesThrustSetpoint(); -// } -// -//private: -// MavlinkOrbSubscription *att_rates_sp_sub; -// uint64_t att_rates_sp_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &); -// MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &); -// -//protected: -// explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(mavlink), -// att_rates_sp_sub(nullptr), -// att_rates_sp_time(0) -// {} -// -// void subscribe() -// { -// att_rates_sp_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_rates_setpoint_s att_rates_sp; -// -// if (att_rates_sp_sub->update(&att_rates_sp_time, &att_rates_sp)) { -// mavlink_msg_roll_pitch_yaw_rates_thrust_setpoint_send(_channel, -// att_rates_sp.timestamp / 1000, -// att_rates_sp.roll, -// att_rates_sp.pitch, -// att_rates_sp.yaw, -// att_rates_sp.thrust); -// } -// } -//}; -// -// -//class MavlinkStreamRCChannelsRaw : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamRCChannelsRaw::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "RC_CHANNELS_RAW"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_RC_CHANNELS_RAW; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamRCChannelsRaw(); -// } -// -//private: -// MavlinkOrbSubscription *rc_sub; -// uint64_t rc_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamRCChannelsRaw(MavlinkStreamRCChannelsRaw &); -// MavlinkStreamRCChannelsRaw& operator = (const MavlinkStreamRCChannelsRaw &); -// -//protected: -// explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(mavlink), -// rc_sub(nullptr), -// rc_time(0) -// {} -// -// void subscribe() -// { -// rc_sub = _mavlink->add_orb_subscription(ORB_ID(input_rc)); -// } -// -// void send(const hrt_abstime t) -// { -// struct rc_input_values rc; -// -// if (rc_sub->update(&rc_time, &rc)) { -// const unsigned port_width = 8; -// -// // Deprecated message (but still needed for compatibility!) -// for (unsigned i = 0; (i * port_width) < rc.channel_count; i++) { -// /* Channels are sent in MAVLink main loop at a fixed interval */ -// mavlink_msg_rc_channels_raw_send(_channel, -// rc.timestamp_publication / 1000, -// i, -// (rc.channel_count > (i * port_width) + 0) ? rc.values[(i * port_width) + 0] : UINT16_MAX, -// (rc.channel_count > (i * port_width) + 1) ? rc.values[(i * port_width) + 1] : UINT16_MAX, -// (rc.channel_count > (i * port_width) + 2) ? rc.values[(i * port_width) + 2] : UINT16_MAX, -// (rc.channel_count > (i * port_width) + 3) ? rc.values[(i * port_width) + 3] : UINT16_MAX, -// (rc.channel_count > (i * port_width) + 4) ? rc.values[(i * port_width) + 4] : UINT16_MAX, -// (rc.channel_count > (i * port_width) + 5) ? rc.values[(i * port_width) + 5] : UINT16_MAX, -// (rc.channel_count > (i * port_width) + 6) ? rc.values[(i * port_width) + 6] : UINT16_MAX, -// (rc.channel_count > (i * port_width) + 7) ? rc.values[(i * port_width) + 7] : UINT16_MAX, -// rc.rssi); -// } -// -// // New message -// mavlink_msg_rc_channels_send(_channel, -// rc.timestamp_publication / 1000, -// rc.channel_count, -// ((rc.channel_count > 0) ? rc.values[0] : UINT16_MAX), -// ((rc.channel_count > 1) ? rc.values[1] : UINT16_MAX), -// ((rc.channel_count > 2) ? rc.values[2] : UINT16_MAX), -// ((rc.channel_count > 3) ? rc.values[3] : UINT16_MAX), -// ((rc.channel_count > 4) ? rc.values[4] : UINT16_MAX), -// ((rc.channel_count > 5) ? rc.values[5] : UINT16_MAX), -// ((rc.channel_count > 6) ? rc.values[6] : UINT16_MAX), -// ((rc.channel_count > 7) ? rc.values[7] : UINT16_MAX), -// ((rc.channel_count > 8) ? rc.values[8] : UINT16_MAX), -// ((rc.channel_count > 9) ? rc.values[9] : UINT16_MAX), -// ((rc.channel_count > 10) ? rc.values[10] : UINT16_MAX), -// ((rc.channel_count > 11) ? rc.values[11] : UINT16_MAX), -// ((rc.channel_count > 12) ? rc.values[12] : UINT16_MAX), -// ((rc.channel_count > 13) ? rc.values[13] : UINT16_MAX), -// ((rc.channel_count > 14) ? rc.values[14] : UINT16_MAX), -// ((rc.channel_count > 15) ? rc.values[15] : UINT16_MAX), -// ((rc.channel_count > 16) ? rc.values[16] : UINT16_MAX), -// ((rc.channel_count > 17) ? rc.values[17] : UINT16_MAX), -// rc.rssi); -// } -// } -//}; -// -// -//class MavlinkStreamManualControl : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamManualControl::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "MANUAL_CONTROL"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_MANUAL_CONTROL; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamManualControl(); -// } -// -//private: -// MavlinkOrbSubscription *manual_sub; -// uint64_t manual_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamManualControl(MavlinkStreamManualControl &); -// MavlinkStreamManualControl& operator = (const MavlinkStreamManualControl &); -// -//protected: -// explicit MavlinkStreamManualControl() : MavlinkStream(mavlink), -// manual_sub(nullptr), -// manual_time(0) -// {} -// -// void subscribe() -// { -// manual_sub = _mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); -// } -// -// void send(const hrt_abstime t) -// { -// struct manual_control_setpoint_s manual; -// -// if (manual_sub->update(&manual_time, &manual)) { -// mavlink_msg_manual_control_send(_channel, -// mavlink_system.sysid, -// manual.x * 1000, -// manual.y * 1000, -// manual.z * 1000, -// manual.r * 1000, -// 0); -// } -// } -//}; -// -// +class MavlinkStreamRollPitchYawThrustSetpoint : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamRollPitchYawThrustSetpoint::get_name_static(); + } + + static const char *get_name_static() + { + return "ROLL_PITCH_YAW_THRUST_SETPOINT"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamRollPitchYawThrustSetpoint(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *att_sp_sub; + uint64_t att_sp_time; + + /* do not allow top copying this class */ + MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &); + MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &); + +protected: + explicit MavlinkStreamRollPitchYawThrustSetpoint(Mavlink *mavlink) : MavlinkStream(mavlink), + att_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint))), + att_sp_time(0) + {} + + void send(const hrt_abstime t) + { + struct vehicle_attitude_setpoint_s att_sp; + + if (att_sp_sub->update(&att_sp_time, &att_sp)) { + mavlink_roll_pitch_yaw_thrust_setpoint_t msg; + + msg.time_boot_ms = att_sp.timestamp / 1000; + msg.roll = att_sp.roll_body; + msg.pitch = att_sp.pitch_body; + msg.yaw = att_sp.yaw_body; + msg.thrust = att_sp.thrust; + + _mavlink->send_message(MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, &msg); + } + } +}; + + +class MavlinkStreamRollPitchYawRatesThrustSetpoint : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static(); + } + + static const char *get_name_static() + { + return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamRollPitchYawRatesThrustSetpoint(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_att_rates_sp_sub; + uint64_t _att_rates_sp_time; + + /* do not allow top copying this class */ + MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &); + MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &); + +protected: + explicit MavlinkStreamRollPitchYawRatesThrustSetpoint(Mavlink *mavlink) : MavlinkStream(mavlink), + _att_rates_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint))), + _att_rates_sp_time(0) + {} + + void send(const hrt_abstime t) + { + struct vehicle_rates_setpoint_s att_rates_sp; + + if (_att_rates_sp_sub->update(&_att_rates_sp_time, &att_rates_sp)) { + mavlink_roll_pitch_yaw_rates_thrust_setpoint_t msg; + + msg.time_boot_ms = att_rates_sp.timestamp / 1000; + msg.roll_rate = att_rates_sp.roll; + msg.pitch_rate = att_rates_sp.pitch; + msg.yaw_rate = att_rates_sp.yaw; + msg.thrust = att_rates_sp.thrust; + + _mavlink->send_message(MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, &msg); + } + } +}; + + +class MavlinkStreamRCChannelsRaw : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamRCChannelsRaw::get_name_static(); + } + + static const char *get_name_static() + { + return "RC_CHANNELS_RAW"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_RC_CHANNELS_RAW; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamRCChannelsRaw(mavlink); + } + + unsigned get_size() + { + return (RC_INPUT_MAX_CHANNELS / 8) * (MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) + + MAVLINK_MSG_ID_RC_CHANNELS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_rc_sub; + uint64_t _rc_time; + + /* do not allow top copying this class */ + MavlinkStreamRCChannelsRaw(MavlinkStreamRCChannelsRaw &); + MavlinkStreamRCChannelsRaw& operator = (const MavlinkStreamRCChannelsRaw &); + +protected: + explicit MavlinkStreamRCChannelsRaw(Mavlink *mavlink) : MavlinkStream(mavlink), + _rc_sub(_mavlink->add_orb_subscription(ORB_ID(input_rc))), + _rc_time(0) + {} + + void send(const hrt_abstime t) + { + struct rc_input_values rc; + + if (_rc_sub->update(&_rc_time, &rc)) { + const unsigned port_width = 8; + + /* deprecated message (but still needed for compatibility!) */ + for (unsigned i = 0; (i * port_width) < rc.channel_count; i++) { + /* channels are sent in MAVLink main loop at a fixed interval */ + mavlink_rc_channels_raw_t msg; + + msg.time_boot_ms = rc.timestamp_publication / 1000; + msg.port = i; + msg.chan1_raw = (rc.channel_count > (i * port_width) + 0) ? rc.values[(i * port_width) + 0] : UINT16_MAX; + msg.chan2_raw = (rc.channel_count > (i * port_width) + 1) ? rc.values[(i * port_width) + 1] : UINT16_MAX; + msg.chan3_raw = (rc.channel_count > (i * port_width) + 2) ? rc.values[(i * port_width) + 2] : UINT16_MAX; + msg.chan4_raw = (rc.channel_count > (i * port_width) + 3) ? rc.values[(i * port_width) + 3] : UINT16_MAX; + msg.chan4_raw = (rc.channel_count > (i * port_width) + 4) ? rc.values[(i * port_width) + 4] : UINT16_MAX; + msg.chan4_raw = (rc.channel_count > (i * port_width) + 5) ? rc.values[(i * port_width) + 5] : UINT16_MAX; + msg.chan4_raw = (rc.channel_count > (i * port_width) + 6) ? rc.values[(i * port_width) + 6] : UINT16_MAX; + msg.chan4_raw = (rc.channel_count > (i * port_width) + 7) ? rc.values[(i * port_width) + 7] : UINT16_MAX; + msg.rssi = rc.rssi; + + _mavlink->send_message(MAVLINK_MSG_ID_RC_CHANNELS_RAW, &msg); + } + + /* new message */ + mavlink_rc_channels_t msg; + + msg.time_boot_ms = rc.timestamp_publication / 1000; + msg.chancount = rc.channel_count; + msg.chan1_raw = (rc.channel_count > 0) ? rc.values[0] : UINT16_MAX; + msg.chan2_raw = (rc.channel_count > 1) ? rc.values[1] : UINT16_MAX; + msg.chan3_raw = (rc.channel_count > 2) ? rc.values[2] : UINT16_MAX; + msg.chan4_raw = (rc.channel_count > 3) ? rc.values[3] : UINT16_MAX; + msg.chan5_raw = (rc.channel_count > 4) ? rc.values[4] : UINT16_MAX; + msg.chan6_raw = (rc.channel_count > 5) ? rc.values[5] : UINT16_MAX; + msg.chan7_raw = (rc.channel_count > 6) ? rc.values[6] : UINT16_MAX; + msg.chan8_raw = (rc.channel_count > 7) ? rc.values[7] : UINT16_MAX; + msg.chan9_raw = (rc.channel_count > 8) ? rc.values[8] : UINT16_MAX; + msg.chan10_raw = (rc.channel_count > 9) ? rc.values[9] : UINT16_MAX; + msg.chan11_raw = (rc.channel_count > 10) ? rc.values[10] : UINT16_MAX; + msg.chan12_raw = (rc.channel_count > 11) ? rc.values[11] : UINT16_MAX; + msg.chan13_raw = (rc.channel_count > 12) ? rc.values[12] : UINT16_MAX; + msg.chan14_raw = (rc.channel_count > 13) ? rc.values[13] : UINT16_MAX; + msg.chan15_raw = (rc.channel_count > 14) ? rc.values[14] : UINT16_MAX; + msg.chan16_raw = (rc.channel_count > 15) ? rc.values[15] : UINT16_MAX; + msg.chan17_raw = (rc.channel_count > 16) ? rc.values[16] : UINT16_MAX; + msg.chan18_raw = (rc.channel_count > 17) ? rc.values[17] : UINT16_MAX; + msg.rssi = rc.rssi; + + _mavlink->send_message(MAVLINK_MSG_ID_RC_CHANNELS, &msg); + } + } +}; + + +class MavlinkStreamManualControl : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamManualControl::get_name_static(); + } + + static const char *get_name_static() + { + return "MANUAL_CONTROL"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_MANUAL_CONTROL; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamManualControl(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_MANUAL_CONTROL_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_manual_sub; + uint64_t _manual_time; + + /* do not allow top copying this class */ + MavlinkStreamManualControl(MavlinkStreamManualControl &); + MavlinkStreamManualControl& operator = (const MavlinkStreamManualControl &); + +protected: + explicit MavlinkStreamManualControl(Mavlink *mavlink) : MavlinkStream(mavlink), + _manual_sub(_mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint))), + _manual_time(0) + {} + + void send(const hrt_abstime t) + { + struct manual_control_setpoint_s manual; + + if (_manual_sub->update(&_manual_time, &manual)) { + mavlink_manual_control_t msg; + + msg.target = mavlink_system.sysid; + msg.x = manual.x * 1000; + msg.y = manual.y * 1000; + msg.z = manual.z * 1000; + msg.r = manual.r * 1000; + msg.buttons = 0; + + _mavlink->send_message(MAVLINK_MSG_ID_MANUAL_CONTROL, &msg); + } + } +}; + + //class MavlinkStreamOpticalFlow : public MavlinkStream //{ //public: @@ -2109,21 +2125,21 @@ StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamAttitude::new_instance, &MavlinkStreamAttitude::get_name_static), new StreamListItem(&MavlinkStreamAttitudeQuaternion::new_instance, &MavlinkStreamAttitudeQuaternion::get_name_static), new StreamListItem(&MavlinkStreamVFRHUD::new_instance, &MavlinkStreamVFRHUD::get_name_static), -// new StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static), -// new StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static), -// new StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static), -// new StreamListItem(&MavlinkStreamGPSGlobalOrigin::new_instance, &MavlinkStreamGPSGlobalOrigin::get_name_static), -// new StreamListItem(&MavlinkStreamServoOutputRaw<0>::new_instance, &MavlinkStreamServoOutputRaw<0>::get_name_static), -// new StreamListItem(&MavlinkStreamServoOutputRaw<1>::new_instance, &MavlinkStreamServoOutputRaw<1>::get_name_static), -// new StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static), -// new StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static), -// new StreamListItem(&MavlinkStreamHILControls::new_instance, &MavlinkStreamHILControls::get_name_static), -// new StreamListItem(&MavlinkStreamGlobalPositionSetpointInt::new_instance, &MavlinkStreamGlobalPositionSetpointInt::get_name_static), -// new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static), -// new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static), -// new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static), -// new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static), -// new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static), + new StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static), + new StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static), + new StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static), + new StreamListItem(&MavlinkStreamGPSGlobalOrigin::new_instance, &MavlinkStreamGPSGlobalOrigin::get_name_static), + new StreamListItem(&MavlinkStreamServoOutputRaw<0>::new_instance, &MavlinkStreamServoOutputRaw<0>::get_name_static), + new StreamListItem(&MavlinkStreamServoOutputRaw<1>::new_instance, &MavlinkStreamServoOutputRaw<1>::get_name_static), + new StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static), + new StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static), + new StreamListItem(&MavlinkStreamHILControls::new_instance, &MavlinkStreamHILControls::get_name_static), + new StreamListItem(&MavlinkStreamGlobalPositionSetpointInt::new_instance, &MavlinkStreamGlobalPositionSetpointInt::get_name_static), + new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static), + new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static), + new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static), + new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static), + new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static), // new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static), // new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static), // new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static), -- cgit v1.2.3 From 019dc1b5264072c785433c53ca11995ed291f924 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 28 Jul 2014 17:46:35 +0200 Subject: mavlink: log message severity fixed --- src/modules/mavlink/mavlink_main.cpp | 27 ++++++++++++++++++++++----- src/modules/mavlink/mavlink_main.h | 2 +- src/modules/mavlink/mavlink_messages.cpp | 19 +------------------ 3 files changed, 24 insertions(+), 24 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 408799be4..f9c7fcedf 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -433,7 +433,24 @@ Mavlink::mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg) const char *txt = (const char *)arg; struct mavlink_logmessage msg; strncpy(msg.text, txt, sizeof(msg.text)); - msg.severity = (unsigned char)cmd; + + switch (cmd) { + case MAVLINK_IOC_SEND_TEXT_INFO: + msg.severity = MAV_SEVERITY_INFO; + break; + + case MAVLINK_IOC_SEND_TEXT_CRITICAL: + msg.severity = MAV_SEVERITY_CRITICAL; + break; + + case MAVLINK_IOC_SEND_TEXT_EMERGENCY: + msg.severity = MAV_SEVERITY_EMERGENCY; + break; + + default: + msg.severity = MAV_SEVERITY_INFO; + break; + } Mavlink *inst; LL_FOREACH(_mavlink_instances, inst) { @@ -816,23 +833,23 @@ Mavlink::handle_message(const mavlink_message_t *msg) void Mavlink::send_statustext_info(const char *string) { - send_statustext(MAVLINK_IOC_SEND_TEXT_INFO, string); + send_statustext(MAV_SEVERITY_INFO, string); } void Mavlink::send_statustext_critical(const char *string) { - send_statustext(MAVLINK_IOC_SEND_TEXT_CRITICAL, string); + send_statustext(MAV_SEVERITY_CRITICAL, string); } void Mavlink::send_statustext_emergency(const char *string) { - send_statustext(MAVLINK_IOC_SEND_TEXT_EMERGENCY, string); + send_statustext(MAV_SEVERITY_EMERGENCY, string); } void -Mavlink::send_statustext(unsigned severity, const char *string) +Mavlink::send_statustext(unsigned char severity, const char *string) { struct mavlink_logmessage logmsg; strncpy(logmsg.text, string, sizeof(logmsg.text)); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 4121e286e..38149cf10 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -218,7 +218,7 @@ public: * @param string the message to send (will be capped by mavlink max string length) * @param severity the log level */ - void send_statustext(unsigned severity, const char *string); + void send_statustext(unsigned char severity, const char *string); MavlinkStream * get_streams() const { return _streams; } diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index a710cdf6a..083a6301a 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -351,24 +351,7 @@ protected: if (lb_ret == OK) { mavlink_statustext_t msg; - /* map severity */ - switch (logmsg.severity) { - case MAVLINK_IOC_SEND_TEXT_INFO: - msg.severity = MAV_SEVERITY_INFO; - break; - - case MAVLINK_IOC_SEND_TEXT_CRITICAL: - msg.severity = MAV_SEVERITY_CRITICAL; - break; - - case MAVLINK_IOC_SEND_TEXT_EMERGENCY: - msg.severity = MAV_SEVERITY_EMERGENCY; - break; - - default: - msg.severity = MAV_SEVERITY_INFO; - break; - } + msg.severity = logmsg.severity; strncpy(msg.text, logmsg.text, sizeof(msg.text)); _mavlink->send_message(MAVLINK_MSG_ID_STATUSTEXT, &msg); -- cgit v1.2.3 From f3ec46369b68d57489a5fa57a320ae99a1bda220 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 28 Jul 2014 20:30:58 +0200 Subject: mavlink: all streams ported to new API --- src/modules/mavlink/mavlink_main.cpp | 1 - src/modules/mavlink/mavlink_messages.cpp | 663 ++++++++++++++++--------------- 2 files changed, 347 insertions(+), 317 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index f9c7fcedf..d72fb8508 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1350,7 +1350,6 @@ Mavlink::task_main(int argc, char *argv[]) configure_stream("GLOBAL_POSITION_INT", 3.0f); configure_stream("LOCAL_POSITION_NED", 3.0f); configure_stream("RC_CHANNELS_RAW", 1.0f); - configure_stream("NAMED_VALUE_FLOAT", 1.0f); configure_stream("GLOBAL_POSITION_SETPOINT_INT", 3.0f); configure_stream("ROLL_PITCH_YAW_THRUST_SETPOINT", 3.0f); configure_stream("DISTANCE_SENSOR", 0.5f); diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 083a6301a..683f0f1e8 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1652,8 +1652,8 @@ public: unsigned get_size() { - return (RC_INPUT_MAX_CHANNELS / 8) * (MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) + - MAVLINK_MSG_ID_RC_CHANNELS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + return _rc_sub->is_published() ? ((RC_INPUT_MAX_CHANNELS / 8) * (MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) + + MAVLINK_MSG_ID_RC_CHANNELS_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0; } private: @@ -1753,7 +1753,7 @@ public: unsigned get_size() { - return MAVLINK_MSG_ID_MANUAL_CONTROL_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + return _manual_sub->is_published() ? (MAVLINK_MSG_ID_MANUAL_CONTROL_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0; } private: @@ -1790,313 +1790,344 @@ protected: }; -//class MavlinkStreamOpticalFlow : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamOpticalFlow::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "OPTICAL_FLOW"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_OPTICAL_FLOW; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamOpticalFlow(); -// } -// -//private: -// MavlinkOrbSubscription *flow_sub; -// uint64_t flow_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamOpticalFlow(MavlinkStreamOpticalFlow &); -// MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &); -// -//protected: -// explicit MavlinkStreamOpticalFlow() : MavlinkStream(mavlink), -// flow_sub(nullptr), -// flow_time(0) -// {} -// -// void subscribe() -// { -// flow_sub = _mavlink->add_orb_subscription(ORB_ID(optical_flow)); -// } -// -// void send(const hrt_abstime t) -// { -// struct optical_flow_s flow; -// -// if (flow_sub->update(&flow_time, &flow)) { -// mavlink_msg_optical_flow_send(_channel, -// flow.timestamp, -// flow.sensor_id, -// flow.flow_raw_x, flow.flow_raw_y, -// flow.flow_comp_x_m, flow.flow_comp_y_m, -// flow.quality, -// flow.ground_distance_m); -// } -// } -//}; -// -//class MavlinkStreamAttitudeControls : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamAttitudeControls::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "ATTITUDE_CONTROLS"; -// } -// -// uint8_t get_id() -// { -// return 0; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamAttitudeControls(); -// } -// -//private: -// MavlinkOrbSubscription *att_ctrl_sub; -// uint64_t att_ctrl_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamAttitudeControls(MavlinkStreamAttitudeControls &); -// MavlinkStreamAttitudeControls& operator = (const MavlinkStreamAttitudeControls &); -// -//protected: -// explicit MavlinkStreamAttitudeControls() : MavlinkStream(mavlink), -// att_ctrl_sub(nullptr), -// att_ctrl_time(0) -// {} -// -// void subscribe() -// { -// att_ctrl_sub = _mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); -// } -// -// void send(const hrt_abstime t) -// { -// struct actuator_controls_s att_ctrl; -// -// if (att_ctrl_sub->update(&att_ctrl_time, &att_ctrl)) { -// /* send, add spaces so that string buffer is at least 10 chars long */ -// mavlink_msg_named_value_float_send(_channel, -// att_ctrl.timestamp / 1000, -// "rll ctrl ", -// att_ctrl.control[0]); -// mavlink_msg_named_value_float_send(_channel, -// att_ctrl.timestamp / 1000, -// "ptch ctrl ", -// att_ctrl.control[1]); -// mavlink_msg_named_value_float_send(_channel, -// att_ctrl.timestamp / 1000, -// "yaw ctrl ", -// att_ctrl.control[2]); -// mavlink_msg_named_value_float_send(_channel, -// att_ctrl.timestamp / 1000, -// "thr ctrl ", -// att_ctrl.control[3]); -// } -// } -//}; -// -//class MavlinkStreamNamedValueFloat : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamNamedValueFloat::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "NAMED_VALUE_FLOAT"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamNamedValueFloat(); -// } -// -//private: -// MavlinkOrbSubscription *debug_sub; -// uint64_t debug_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamNamedValueFloat(MavlinkStreamNamedValueFloat &); -// MavlinkStreamNamedValueFloat& operator = (const MavlinkStreamNamedValueFloat &); -// -//protected: -// explicit MavlinkStreamNamedValueFloat() : MavlinkStream(mavlink), -// debug_sub(nullptr), -// debug_time(0) -// {} -// -// void subscribe() -// { -// debug_sub = _mavlink->add_orb_subscription(ORB_ID(debug_key_value)); -// } -// -// void send(const hrt_abstime t) -// { -// struct debug_key_value_s debug; -// -// if (debug_sub->update(&debug_time, &debug)) { -// /* enforce null termination */ -// debug.key[sizeof(debug.key) - 1] = '\0'; -// -// mavlink_msg_named_value_float_send(_channel, -// debug.timestamp_ms, -// debug.key, -// debug.value); -// } -// } -//}; -// -//class MavlinkStreamCameraCapture : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamCameraCapture::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "CAMERA_CAPTURE"; -// } -// -// uint8_t get_id() -// { -// return 0; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamCameraCapture(); -// } -// -//private: -// MavlinkOrbSubscription *status_sub; -// -// /* do not allow top copying this class */ -// MavlinkStreamCameraCapture(MavlinkStreamCameraCapture &); -// MavlinkStreamCameraCapture& operator = (const MavlinkStreamCameraCapture &); -// -//protected: -// explicit MavlinkStreamCameraCapture() : MavlinkStream(mavlink), -// status_sub(nullptr) -// {} -// -// void subscribe() -// { -// status_sub = _mavlink->add_orb_subscription(ORB_ID(vehicle_status)); -// } -// -// void send(const hrt_abstime t) -// { -// struct vehicle_status_s status; -// (void)status_sub->update(&status); -// -// if (status.arming_state == ARMING_STATE_ARMED -// || status.arming_state == ARMING_STATE_ARMED_ERROR) { -// -// /* send camera capture on */ -// mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 1, 0, 0, 0); -// -// } else { -// /* send camera capture off */ -// mavlink_msg_command_long_send(_channel, mavlink_system.sysid, 0, MAV_CMD_DO_CONTROL_VIDEO, 0, 0, 0, 0, 0, 0, 0, 0); -// } -// } -//}; -// -//class MavlinkStreamDistanceSensor : public MavlinkStream -//{ -//public: -// const char *get_name() const -// { -// return MavlinkStreamDistanceSensor::get_name_static(); -// } -// -// static const char *get_name_static() -// { -// return "DISTANCE_SENSOR"; -// } -// -// uint8_t get_id() -// { -// return MAVLINK_MSG_ID_DISTANCE_SENSOR; -// } -// -// static MavlinkStream *new_instance(Mavlink *mavlink) -// { -// return new MavlinkStreamDistanceSensor(); -// } -// -//private: -// MavlinkOrbSubscription *range_sub; -// uint64_t range_time; -// -// /* do not allow top copying this class */ -// MavlinkStreamDistanceSensor(MavlinkStreamDistanceSensor &); -// MavlinkStreamDistanceSensor& operator = (const MavlinkStreamDistanceSensor &); -// -//protected: -// explicit MavlinkStreamDistanceSensor() : MavlinkStream(mavlink), -// range_sub(nullptr), -// range_time(0) -// {} -// -// void subscribe() -// { -// range_sub = _mavlink->add_orb_subscription(ORB_ID(sensor_range_finder)); -// } -// -// void send(const hrt_abstime t) -// { -// struct range_finder_report range; -// -// if (range_sub->update(&range_time, &range)) { -// -// uint8_t type; -// -// switch (range.type) { -// case RANGE_FINDER_TYPE_LASER: -// type = MAV_DISTANCE_SENSOR_LASER; -// break; -// } -// -// uint8_t id = 0; -// uint8_t orientation = 0; -// uint8_t covariance = 20; -// -// mavlink_msg_distance_sensor_send(_channel, range.timestamp / 1000, type, id, orientation, -// range.minimum_distance*100, range.maximum_distance*100, range.distance*100, covariance); -// } -// } -//}; +class MavlinkStreamOpticalFlow : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamOpticalFlow::get_name_static(); + } + + static const char *get_name_static() + { + return "OPTICAL_FLOW"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_OPTICAL_FLOW; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamOpticalFlow(mavlink); + } + + unsigned get_size() + { + return _flow_sub->is_published() ? (MAVLINK_MSG_ID_OPTICAL_FLOW_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0; + } + +private: + MavlinkOrbSubscription *_flow_sub; + uint64_t _flow_time; + + /* do not allow top copying this class */ + MavlinkStreamOpticalFlow(MavlinkStreamOpticalFlow &); + MavlinkStreamOpticalFlow& operator = (const MavlinkStreamOpticalFlow &); + +protected: + explicit MavlinkStreamOpticalFlow(Mavlink *mavlink) : MavlinkStream(mavlink), + _flow_sub(_mavlink->add_orb_subscription(ORB_ID(optical_flow))), + _flow_time(0) + {} + + void send(const hrt_abstime t) + { + struct optical_flow_s flow; + + if (_flow_sub->update(&_flow_time, &flow)) { + mavlink_optical_flow_t msg; + + msg.time_usec = flow.timestamp; + msg.sensor_id = flow.sensor_id; + msg.flow_x = flow.flow_raw_x; + msg.flow_y = flow.flow_raw_y; + msg.flow_comp_m_x = flow.flow_comp_x_m; + msg.flow_comp_m_y = flow.flow_comp_y_m; + msg.quality = flow.quality; + msg.ground_distance = flow.ground_distance_m; + + _mavlink->send_message(MAVLINK_MSG_ID_OPTICAL_FLOW, &msg); + } + } +}; + +class MavlinkStreamAttitudeControls : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamAttitudeControls::get_name_static(); + } + + static const char *get_name_static() + { + return "ATTITUDE_CONTROLS"; + } + + uint8_t get_id() + { + return 0; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamAttitudeControls(mavlink); + } + + unsigned get_size() + { + return 4 * (MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES); + } + +private: + MavlinkOrbSubscription *_att_ctrl_sub; + uint64_t _att_ctrl_time; + + /* do not allow top copying this class */ + MavlinkStreamAttitudeControls(MavlinkStreamAttitudeControls &); + MavlinkStreamAttitudeControls& operator = (const MavlinkStreamAttitudeControls &); + +protected: + explicit MavlinkStreamAttitudeControls(Mavlink *mavlink) : MavlinkStream(mavlink), + _att_ctrl_sub(_mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS)), + _att_ctrl_time(0) + {} + + void send(const hrt_abstime t) + { + struct actuator_controls_s att_ctrl; + + if (_att_ctrl_sub->update(&_att_ctrl_time, &att_ctrl)) { + /* send, add spaces so that string buffer is at least 10 chars long */ + mavlink_named_value_float_t msg; + + msg.time_boot_ms = att_ctrl.timestamp / 1000; + + snprintf(msg.name, sizeof(msg.name), "rll ctrl"); + msg.value = att_ctrl.control[0]; + + _mavlink->send_message(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, &msg); + + snprintf(msg.name, sizeof(msg.name), "ptch ctrl"); + msg.value = att_ctrl.control[1]; + + _mavlink->send_message(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, &msg); + + snprintf(msg.name, sizeof(msg.name), "yaw ctrl"); + msg.value = att_ctrl.control[2]; + + _mavlink->send_message(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, &msg); + + snprintf(msg.name, sizeof(msg.name), "thr ctrl"); + msg.value = att_ctrl.control[3]; + + _mavlink->send_message(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, &msg); + } + } +}; + + +class MavlinkStreamNamedValueFloat : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamNamedValueFloat::get_name_static(); + } + + static const char *get_name_static() + { + return "NAMED_VALUE_FLOAT"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_NAMED_VALUE_FLOAT; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamNamedValueFloat(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_debug_sub; + uint64_t _debug_time; + + /* do not allow top copying this class */ + MavlinkStreamNamedValueFloat(MavlinkStreamNamedValueFloat &); + MavlinkStreamNamedValueFloat& operator = (const MavlinkStreamNamedValueFloat &); + +protected: + explicit MavlinkStreamNamedValueFloat(Mavlink *mavlink) : MavlinkStream(mavlink), + _debug_sub(_mavlink->add_orb_subscription(ORB_ID(debug_key_value))), + _debug_time(0) + {} + + void send(const hrt_abstime t) + { + struct debug_key_value_s debug; + + if (_debug_sub->update(&_debug_time, &debug)) { + mavlink_named_value_float_t msg; + + msg.time_boot_ms = debug.timestamp_ms; + memcpy(msg.name, debug.key, sizeof(msg.name)); + /* enforce null termination */ + msg.name[sizeof(msg.name) - 1] = '\0'; + msg.value = debug.value; + + _mavlink->send_message(MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, &msg); + } + } +}; + + +class MavlinkStreamCameraCapture : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamCameraCapture::get_name_static(); + } + + static const char *get_name_static() + { + return "CAMERA_CAPTURE"; + } + + uint8_t get_id() + { + return 0; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamCameraCapture(mavlink); + } + + unsigned get_size() + { + return MAVLINK_MSG_ID_COMMAND_LONG_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + } + +private: + MavlinkOrbSubscription *_status_sub; + + /* do not allow top copying this class */ + MavlinkStreamCameraCapture(MavlinkStreamCameraCapture &); + MavlinkStreamCameraCapture& operator = (const MavlinkStreamCameraCapture &); + +protected: + explicit MavlinkStreamCameraCapture(Mavlink *mavlink) : MavlinkStream(mavlink), + _status_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_status))) + {} + + void send(const hrt_abstime t) + { + struct vehicle_status_s status; + (void)_status_sub->update(&status); + + mavlink_command_long_t msg; + + msg.target_system = mavlink_system.sysid; + msg.target_component = MAV_COMP_ID_ALL; + msg.command = MAV_CMD_DO_CONTROL_VIDEO; + msg.confirmation = 0; + msg.param1 = 0; + msg.param2 = 0; + msg.param3 = 0; + /* set camera capture ON/OFF depending on arming state */ + msg.param4 = (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) ? 1 : 0; + msg.param5 = 0; + msg.param6 = 0; + msg.param7 = 0; + + _mavlink->send_message(MAVLINK_MSG_ID_COMMAND_LONG, &msg); + } +}; + + +class MavlinkStreamDistanceSensor : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamDistanceSensor::get_name_static(); + } + + static const char *get_name_static() + { + return "DISTANCE_SENSOR"; + } + + uint8_t get_id() + { + return MAVLINK_MSG_ID_DISTANCE_SENSOR; + } + + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamDistanceSensor(mavlink); + } + + unsigned get_size() + { + return _range_sub->is_published() ? (MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) : 0; + } + +private: + MavlinkOrbSubscription *_range_sub; + uint64_t _range_time; + + /* do not allow top copying this class */ + MavlinkStreamDistanceSensor(MavlinkStreamDistanceSensor &); + MavlinkStreamDistanceSensor& operator = (const MavlinkStreamDistanceSensor &); + +protected: + explicit MavlinkStreamDistanceSensor(Mavlink *mavlink) : MavlinkStream(mavlink), + _range_sub(_mavlink->add_orb_subscription(ORB_ID(sensor_range_finder))), + _range_time(0) + {} + + void send(const hrt_abstime t) + { + struct range_finder_report range; + + if (_range_sub->update(&_range_time, &range)) { + + mavlink_distance_sensor_t msg; + + msg.time_boot_ms = range.timestamp / 1000; + + switch (range.type) { + case RANGE_FINDER_TYPE_LASER: + msg.type = MAV_DISTANCE_SENSOR_LASER; + break; + + default: + msg.type = MAV_DISTANCE_SENSOR_LASER; + break; + } + + msg.id = 0; + msg.orientation = 0; + msg.min_distance = range.minimum_distance * 100; + msg.max_distance = range.minimum_distance * 100; + msg.current_distance = range.distance * 100; + msg.covariance = 20; + + _mavlink->send_message(MAVLINK_MSG_ID_DISTANCE_SENSOR, &msg); + } + } +}; StreamListItem *streams_list[] = { @@ -2111,6 +2142,7 @@ StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamGPSRawInt::new_instance, &MavlinkStreamGPSRawInt::get_name_static), new StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static), new StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static), + new StreamListItem(&MavlinkStreamViconPositionEstimate::new_instance, &MavlinkStreamViconPositionEstimate::get_name_static), new StreamListItem(&MavlinkStreamGPSGlobalOrigin::new_instance, &MavlinkStreamGPSGlobalOrigin::get_name_static), new StreamListItem(&MavlinkStreamServoOutputRaw<0>::new_instance, &MavlinkStreamServoOutputRaw<0>::get_name_static), new StreamListItem(&MavlinkStreamServoOutputRaw<1>::new_instance, &MavlinkStreamServoOutputRaw<1>::get_name_static), @@ -2123,11 +2155,10 @@ StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static), new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static), new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static), -// new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static), -// new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static), -// new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static), -// new StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static), -// new StreamListItem(&MavlinkStreamDistanceSensor::new_instance, &MavlinkStreamDistanceSensor::get_name_static), -// new StreamListItem(&MavlinkStreamViconPositionEstimate::new_instance, &MavlinkStreamViconPositionEstimate::get_name_static), + new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static), + new StreamListItem(&MavlinkStreamAttitudeControls::new_instance, &MavlinkStreamAttitudeControls::get_name_static), + new StreamListItem(&MavlinkStreamNamedValueFloat::new_instance, &MavlinkStreamNamedValueFloat::get_name_static), + new StreamListItem(&MavlinkStreamCameraCapture::new_instance, &MavlinkStreamCameraCapture::get_name_static), + new StreamListItem(&MavlinkStreamDistanceSensor::new_instance, &MavlinkStreamDistanceSensor::get_name_static), nullptr }; -- cgit v1.2.3 From 129c93f22f0717d9d85910de87fecece9fabbc79 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 11:11:58 +0200 Subject: Revert "Remove all unused TECS parameters" This reverts commit ce78b399691d43bd150c0a5928f08c98076a3892. Conflicts: src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 57 +++++++ .../fw_pos_control_l1/fw_pos_control_l1_params.c | 176 +++++++++++++++++++++ 2 files changed, 233 insertions(+) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 0b111f7bd..a1bc5c24e 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -199,6 +199,19 @@ private: float l1_period; float l1_damping; + float time_const; + float min_sink_rate; + float max_sink_rate; + float max_climb_rate; + float throttle_damp; + float integrator_gain; + float vertical_accel_limit; + float height_comp_filter_omega; + float speed_comp_filter_omega; + float roll_throttle_compensation; + float speed_weight; + float pitch_damping; + float airspeed_min; float airspeed_trim; float airspeed_max; @@ -226,6 +239,19 @@ private: param_t l1_period; param_t l1_damping; + param_t time_const; + param_t min_sink_rate; + param_t max_sink_rate; + param_t max_climb_rate; + param_t throttle_damp; + param_t integrator_gain; + param_t vertical_accel_limit; + param_t height_comp_filter_omega; + param_t speed_comp_filter_omega; + param_t roll_throttle_compensation; + param_t speed_weight; + param_t pitch_damping; + param_t airspeed_min; param_t airspeed_trim; param_t airspeed_max; @@ -438,6 +464,21 @@ FixedwingPositionControl::FixedwingPositionControl() : _parameter_handles.land_heading_hold_horizontal_distance = param_find("FW_LND_HHDIST"); _parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT"); + _parameter_handles.time_const = param_find("FW_T_TIME_CONST"); + _parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN"); + _parameter_handles.max_sink_rate = param_find("FW_T_SINK_MAX"); + _parameter_handles.max_climb_rate = param_find("FW_T_CLMB_MAX"); + _parameter_handles.throttle_damp = param_find("FW_T_THR_DAMP"); + _parameter_handles.integrator_gain = param_find("FW_T_INTEG_GAIN"); + _parameter_handles.vertical_accel_limit = param_find("FW_T_VERT_ACC"); + _parameter_handles.height_comp_filter_omega = param_find("FW_T_HGT_OMEGA"); + _parameter_handles.speed_comp_filter_omega = param_find("FW_T_SPD_OMEGA"); + _parameter_handles.roll_throttle_compensation = param_find("FW_T_RLL2THR"); + _parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT"); + _parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP"); + _parameter_handles.heightrate_p = param_find("FW_T_HRATE_P"); + _parameter_handles.speedrate_p = param_find("FW_T_SRATE_P"); + /* fetch initial parameter values */ parameters_update(); } @@ -488,6 +529,22 @@ FixedwingPositionControl::parameters_update() param_get(_parameter_handles.throttle_land_max, &(_parameters.throttle_land_max)); + param_get(_parameter_handles.time_const, &(_parameters.time_const)); + param_get(_parameter_handles.min_sink_rate, &(_parameters.min_sink_rate)); + param_get(_parameter_handles.max_sink_rate, &(_parameters.max_sink_rate)); + param_get(_parameter_handles.throttle_damp, &(_parameters.throttle_damp)); + param_get(_parameter_handles.integrator_gain, &(_parameters.integrator_gain)); + param_get(_parameter_handles.vertical_accel_limit, &(_parameters.vertical_accel_limit)); + param_get(_parameter_handles.height_comp_filter_omega, &(_parameters.height_comp_filter_omega)); + param_get(_parameter_handles.speed_comp_filter_omega, &(_parameters.speed_comp_filter_omega)); + param_get(_parameter_handles.roll_throttle_compensation, &(_parameters.roll_throttle_compensation)); + param_get(_parameter_handles.speed_weight, &(_parameters.speed_weight)); + param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping)); + param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate)); + + param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p)); + param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p)); + param_get(_parameter_handles.land_slope_angle, &(_parameters.land_slope_angle)); param_get(_parameter_handles.land_H1_virt, &(_parameters.land_H1_virt)); param_get(_parameter_handles.land_flare_alt_relative, &(_parameters.land_flare_alt_relative)); diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 27039ff51..52128e1b7 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -154,6 +154,182 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); */ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f); +/** + * Maximum climb rate + * + * This is the best climb rate that the aircraft can achieve with + * the throttle set to THR_MAX and the airspeed set to the + * default value. For electric aircraft make sure this number can be + * achieved towards the end of flight when the battery voltage has reduced. + * The setting of this parameter can be checked by commanding a positive + * altitude change of 100m in loiter, RTL or guided mode. If the throttle + * required to climb is close to THR_MAX and the aircraft is maintaining + * airspeed, then this parameter is set correctly. If the airspeed starts + * to reduce, then the parameter is set to high, and if the throttle + * demand required to climb and maintain speed is noticeably less than + * FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or + * FW_THR_MAX reduced. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f); + +/** + * Minimum descent rate + * + * This is the sink rate of the aircraft with the throttle + * set to THR_MIN and flown at the same airspeed as used + * to measure FW_T_CLMB_MAX. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); + +/** + * Maximum descent rate + * + * This sets the maximum descent rate that the controller will use. + * If this value is too large, the aircraft can over-speed on descent. + * This should be set to a value that can be achieved without + * exceeding the lower pitch angle limit and without over-speeding + * the aircraft. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); + +/** + * TECS time constant + * + * This is the time constant of the TECS control algorithm (in seconds). + * Smaller values make it faster to respond, larger values make it slower + * to respond. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f); + +/** + * Throttle damping factor + * + * This is the damping gain for the throttle demand loop. + * Increase to add damping to correct for oscillations in speed and height. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f); + +/** + * Integrator gain + * + * This is the integrator gain on the control loop. + * Increasing this gain increases the speed at which speed + * and height offsets are trimmed out, but reduces damping and + * increases overshoot. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); + +/** + * Maximum vertical acceleration + * + * This is the maximum vertical acceleration (in metres/second square) + * either up or down that the controller will use to correct speed + * or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g) + * allows for reasonably aggressive pitch changes if required to recover + * from under-speed conditions. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); + +/** + * Complementary filter "omega" parameter for height + * + * This is the cross-over frequency (in radians/second) of the complementary + * filter used to fuse vertical acceleration and barometric height to obtain + * an estimate of height rate and height. Increasing this frequency weights + * the solution more towards use of the barometer, whilst reducing it weights + * the solution more towards use of the accelerometer data. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f); + +/** + * Complementary filter "omega" parameter for speed + * + * This is the cross-over frequency (in radians/second) of the complementary + * filter used to fuse longitudinal acceleration and airspeed to obtain an + * improved airspeed estimate. Increasing this frequency weights the solution + * more towards use of the arispeed sensor, whilst reducing it weights the + * solution more towards use of the accelerometer data. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); + +/** + * Roll -> Throttle feedforward + * + * Increasing this gain turn increases the amount of throttle that will + * be used to compensate for the additional drag created by turning. + * Ideally this should be set to approximately 10 x the extra sink rate + * in m/s created by a 45 degree bank turn. Increase this gain if + * the aircraft initially loses energy in turns and reduce if the + * aircraft initially gains energy in turns. Efficient high aspect-ratio + * aircraft (eg powered sailplanes) can use a lower value, whereas + * inefficient low aspect-ratio models (eg delta wings) can use a higher value. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f); + +/** + * Speed <--> Altitude priority + * + * This parameter adjusts the amount of weighting that the pitch control + * applies to speed vs height errors. Setting it to 0.0 will cause the + * pitch control to control height and ignore speed errors. This will + * normally improve height accuracy but give larger airspeed errors. + * Setting it to 2.0 will cause the pitch control loop to control speed + * and ignore height errors. This will normally reduce airspeed errors, + * but give larger height errors. The default value of 1.0 allows the pitch + * control to simultaneously control height and speed. + * Note to Glider Pilots - set this parameter to 2.0 (The glider will + * adjust its pitch angle to maintain airspeed, ignoring changes in height). + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); + +/** + * Pitch damping factor + * + * This is the damping gain for the pitch demand loop. Increase to add + * damping to correct for oscillations in height. The default value of 0.0 + * will work well provided the pitch to servo controller has been tuned + * properly. + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f); + +/** + * Height rate P factor + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f); + +/** + * Speed rate P factor + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f); + /** * Landing slope angle * -- cgit v1.2.3 From af7385bdc268bf4f19e9d1291a3d753a2c634ef0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 11:15:23 +0200 Subject: Re-instate TECS default gains --- ROMFS/px4fmu_common/init.d/rc.fw_defaults | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.fw_defaults b/ROMFS/px4fmu_common/init.d/rc.fw_defaults index 3a50fcf56..3c336f295 100644 --- a/ROMFS/px4fmu_common/init.d/rc.fw_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.fw_defaults @@ -11,4 +11,8 @@ then param set NAV_RTL_ALT 100 param set NAV_RTL_LAND_T -1 param set NAV_ACCEPT_RAD 50 + param set FW_T_HRATE_P 0.01 + param set FW_T_RLL2THR 15 + param set FW_T_SRATE_P 0.01 + param set FW_T_TIME_CONST 5 fi \ No newline at end of file -- cgit v1.2.3 From ae2de675014c701b45710b646f3a816ad2222b73 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 11:24:11 +0200 Subject: Revert "Remove old TECS implementation - we can really only decently flight-test and support one." This reverts commit 503ded05394767d58359834e73bc63672b701dbe. Conflicts: mavlink/include/mavlink/v1.0 src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp --- makefiles/config_aerocore_default.mk | 1 + makefiles/config_px4fmu-v1_default.mk | 1 + makefiles/config_px4fmu-v2_default.mk | 1 + .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 74 +++++++++++++++++----- 4 files changed, 61 insertions(+), 16 deletions(-) diff --git a/makefiles/config_aerocore_default.mk b/makefiles/config_aerocore_default.mk index 53a2ad1ab..0d3934bd0 100644 --- a/makefiles/config_aerocore_default.mk +++ b/makefiles/config_aerocore_default.mk @@ -80,6 +80,7 @@ LIBRARIES += lib/mathlib/CMSIS MODULES += lib/mathlib MODULES += lib/mathlib/math/filter MODULES += lib/ecl +MODULES += lib/external_lgpl MODULES += lib/geo MODULES += lib/geo_lookup MODULES += lib/conversion diff --git a/makefiles/config_px4fmu-v1_default.mk b/makefiles/config_px4fmu-v1_default.mk index cc0958c29..a7c10f52f 100644 --- a/makefiles/config_px4fmu-v1_default.mk +++ b/makefiles/config_px4fmu-v1_default.mk @@ -108,6 +108,7 @@ LIBRARIES += lib/mathlib/CMSIS MODULES += lib/mathlib MODULES += lib/mathlib/math/filter MODULES += lib/ecl +MODULES += lib/external_lgpl MODULES += lib/geo MODULES += lib/geo_lookup MODULES += lib/conversion diff --git a/makefiles/config_px4fmu-v2_default.mk b/makefiles/config_px4fmu-v2_default.mk index a498a1b40..d0a40445d 100644 --- a/makefiles/config_px4fmu-v2_default.mk +++ b/makefiles/config_px4fmu-v2_default.mk @@ -121,6 +121,7 @@ LIBRARIES += lib/mathlib/CMSIS MODULES += lib/mathlib MODULES += lib/mathlib/math/filter MODULES += lib/ecl +MODULES += lib/external_lgpl MODULES += lib/geo MODULES += lib/geo_lookup MODULES += lib/conversion diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index a1bc5c24e..78e91bbfd 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -42,8 +42,8 @@ * Proceedings of the AIAA Guidance, Navigation and Control * Conference, Aug 2004. AIAA-2004-4900. * - * Implementation for total energy control class: - * Thomas Gubler + * Original implementation for total energy control class: + * Paul Riseborough and Andrew Tridgell, 2013 (code in lib/external_lgpl) * * More details and acknowledgements in the referenced library headers. * @@ -87,6 +87,7 @@ #include #include #include +#include #include #include "landingslope.h" #include "mtecs/mTecs.h" @@ -192,6 +193,7 @@ private: math::Matrix<3, 3> _R_nb; ///< current attitude ECL_L1_Pos_Controller _l1_control; + TECS _tecs; fwPosctrl::mTecs _mTecs; bool _was_pos_control_mode; @@ -557,6 +559,23 @@ FixedwingPositionControl::parameters_update() _l1_control.set_l1_period(_parameters.l1_period); _l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit)); + _tecs.set_time_const(_parameters.time_const); + _tecs.set_min_sink_rate(_parameters.min_sink_rate); + _tecs.set_max_sink_rate(_parameters.max_sink_rate); + _tecs.set_throttle_damp(_parameters.throttle_damp); + _tecs.set_integrator_gain(_parameters.integrator_gain); + _tecs.set_vertical_accel_limit(_parameters.vertical_accel_limit); + _tecs.set_height_comp_filter_omega(_parameters.height_comp_filter_omega); + _tecs.set_speed_comp_filter_omega(_parameters.speed_comp_filter_omega); + _tecs.set_roll_throttle_compensation(_parameters.roll_throttle_compensation); + _tecs.set_speed_weight(_parameters.speed_weight); + _tecs.set_pitch_damping(_parameters.pitch_damping); + _tecs.set_indicated_airspeed_min(_parameters.airspeed_min); + _tecs.set_indicated_airspeed_max(_parameters.airspeed_max); + _tecs.set_max_climb_rate(_parameters.max_climb_rate); + _tecs.set_heightrate_p(_parameters.heightrate_p); + _tecs.set_speedrate_p(_parameters.speedrate_p); + /* sanity check parameters */ if (_parameters.airspeed_max < _parameters.airspeed_min || _parameters.airspeed_max < 5.0f || @@ -618,6 +637,9 @@ FixedwingPositionControl::vehicle_airspeed_poll() } } + /* update TECS state */ + _tecs.enable_airspeed(_airspeed_valid); + return airspeed_updated; } @@ -790,6 +812,14 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi float eas2tas = 1.0f; // XXX calculate actual number based on current measurements + /* filter speed and altitude for controller */ + math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2); + math::Vector<3> accel_earth = _R_nb * accel_body; + + if (!_mTecs.getEnabled()) { + _tecs.update_50hz(_global_pos.alt /* XXX might switch to alt err here */, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth); + } + /* define altitude error */ float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt; @@ -815,6 +845,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi /* get circle mode */ bool was_circle_mode = _l1_control.circle_mode(); + /* restore speed weight, in case changed intermittently (e.g. in landing handling) */ + _tecs.set_speed_weight(_parameters.speed_weight); + /* current waypoint (the one currently heading for) */ math::Vector<2> next_wp((float)pos_sp_triplet.current.lat, (float)pos_sp_triplet.current.lon); @@ -1123,9 +1156,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi _att_sp.thrust = launchDetector.getThrottlePreTakeoff(); } else { - _att_sp.thrust = math::min(_mTecs.getThrottleSetpoint(), throttle_max); + _att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() :_tecs.get_throttle_demand(), throttle_max); } - _att_sp.pitch_body = _mTecs.getPitchSetpoint(); + _att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand(); if (_control_mode.flag_control_position_enabled) { last_manual = false; @@ -1305,20 +1338,29 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_ const math::Vector<3> &ground_speed, tecs_mode mode) { - /* Using mtecs library: prepare arguments for mtecs call */ - float flightPathAngle = 0.0f; - float ground_speed_length = ground_speed.length(); - if (ground_speed_length > FLT_EPSILON) { - flightPathAngle = -asinf(ground_speed(2)/ground_speed_length); - } - fwPosctrl::LimitOverride limitOverride; - if (climbout_mode) { - limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad); + if (_mTecs.getEnabled()) { + /* Using mtecs library: prepare arguments for mtecs call */ + float flightPathAngle = 0.0f; + float ground_speed_length = ground_speed.length(); + if (ground_speed_length > FLT_EPSILON) { + flightPathAngle = -asinf(ground_speed(2)/ground_speed_length); + } + fwPosctrl::LimitOverride limitOverride; + if (climbout_mode) { + limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad); + } else { + limitOverride.disablePitchMinOverride(); + } + _mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode, + limitOverride); } else { - limitOverride.disablePitchMinOverride(); + /* Using tecs library */ + _tecs.update_pitch_throttle(_R_nb, _att.pitch, altitude, alt_sp, v_sp, + _airspeed.indicated_airspeed_m_s, eas2tas, + climbout_mode, climbout_pitch_min_rad, + throttle_min, throttle_max, throttle_cruise, + pitch_min_rad, pitch_max_rad); } - _mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode, - limitOverride); } int -- cgit v1.2.3 From 2b55eb605ed2216f9f73f5745de7d7a34c851e1c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 11:27:59 +0200 Subject: Make airspeed filter a bit smoother, but do not induce a huge phase delay --- src/drivers/meas_airspeed/meas_airspeed.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 03e50e5cb..9cfa7f383 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -103,7 +103,7 @@ /* Measurement rate is 100Hz */ #define MEAS_RATE 100 -#define MEAS_DRIVER_FILTER_FREQ 0.8f +#define MEAS_DRIVER_FILTER_FREQ 1.5f #define CONVERSION_INTERVAL (1000000 / MEAS_RATE) /* microseconds */ class MEASAirspeed : public Airspeed -- cgit v1.2.3 From 5171286bbb7eef115bd7fc711f2c8fcebd432e4d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 11:34:46 +0200 Subject: Re-add two params that fell off the truck before --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 78e91bbfd..f0e18d1bb 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -205,6 +205,8 @@ private: float min_sink_rate; float max_sink_rate; float max_climb_rate; + float heightrate_p; + float speedrate_p; float throttle_damp; float integrator_gain; float vertical_accel_limit; @@ -245,6 +247,8 @@ private: param_t min_sink_rate; param_t max_sink_rate; param_t max_climb_rate; + param_t heightrate_p; + param_t speedrate_p; param_t throttle_damp; param_t integrator_gain; param_t vertical_accel_limit; -- cgit v1.2.3 From c1d3f592b4082333ac454ab62dbdf685d41b3bb6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 11:36:59 +0200 Subject: Make ext libs more flash efficient --- src/lib/external_lgpl/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/lib/external_lgpl/module.mk b/src/lib/external_lgpl/module.mk index 53f1629e3..29d3514f6 100644 --- a/src/lib/external_lgpl/module.mk +++ b/src/lib/external_lgpl/module.mk @@ -46,3 +46,5 @@ # SRCS = tecs/tecs.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 1bd57f1dbfb9c9896fabf71cec292aa7024a33ec Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 11:37:12 +0200 Subject: Make ECL more flash efficient --- src/lib/ecl/module.mk | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/lib/ecl/module.mk b/src/lib/ecl/module.mk index f2aa3db6a..93a5b511f 100644 --- a/src/lib/ecl/module.mk +++ b/src/lib/ecl/module.mk @@ -39,3 +39,5 @@ SRCS = attitude_fw/ecl_pitch_controller.cpp \ attitude_fw/ecl_roll_controller.cpp \ attitude_fw/ecl_yaw_controller.cpp \ l1/ecl_l1_pos_controller.cpp + +MAXOPTIMIZATION = -Os -- cgit v1.2.3 From 2cf688312a83d3c8ad5b813de0643901891886c0 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 29 Jul 2014 11:58:59 +0200 Subject: mavlink: show 'rate mult' in 'mavlink status' output --- src/modules/mavlink/mavlink_main.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 4ae90c344..69beb9cc9 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1660,6 +1660,7 @@ Mavlink::display_status() printf("\ttx: %.3f kB/s\n", (double)_rate_tx); printf("\ttxerr: %.3f kB/s\n", (double)_rate_txerr); printf("\trx: %.3f kB/s\n", (double)_rate_rx); + printf("\trate mult: %.3f\n", (double)_rate_mult); } int -- cgit v1.2.3 From e3bc5571556d043ad5c8c4fcabd1f9b371599397 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 29 Jul 2014 11:59:38 +0200 Subject: rc.usb: set RC_CHANNELS_RAW rate to 5Hz --- ROMFS/px4fmu_common/init.d/rc.usb | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index d31ef11cf..eb6039b4c 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -19,6 +19,8 @@ mavlink stream -d /dev/ttyACM0 -s ATTITUDE -r 20 usleep 100000 mavlink stream -d /dev/ttyACM0 -s ATTITUDE_CONTROLS -r 30 usleep 100000 +mavlink stream -d /dev/ttyACM0 -s RC_CHANNELS_RAW -r 5 +usleep 100000 mavlink stream -d /dev/ttyACM0 -s SERVO_OUTPUT_RAW_0 -r 20 usleep 100000 mavlink stream -d /dev/ttyACM0 -s GLOBAL_POSITION_SETPOINT_INT -r 20 -- cgit v1.2.3 From c9eea8fbfaad7bfb3eee36a49588c9ac3a42ddc6 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 29 Jul 2014 12:01:09 +0200 Subject: nshterm: increase stack size to fix crash on 'ls -l' --- src/systemcmds/nshterm/module.mk | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/systemcmds/nshterm/module.mk b/src/systemcmds/nshterm/module.mk index b22b446da..e2fa0ff80 100644 --- a/src/systemcmds/nshterm/module.mk +++ b/src/systemcmds/nshterm/module.mk @@ -38,4 +38,4 @@ MODULE_COMMAND = nshterm SRCS = nshterm.c -MODULE_STACKSIZE = 1200 +MODULE_STACKSIZE = 1400 -- cgit v1.2.3 From 5a7a6bca777317cc69840c35b82c50486dd061e7 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Tue, 29 Jul 2014 16:02:58 +0200 Subject: fetch_log.py renamed to fetch_file.py and reworked, works with all files, not only logs, added recursive directory download --- Tools/fetch_file.py | 207 ++++++++++++++++++++++++++++++++++++++++++++++++++++ Tools/fetch_log.py | 133 --------------------------------- 2 files changed, 207 insertions(+), 133 deletions(-) create mode 100644 Tools/fetch_file.py delete mode 100644 Tools/fetch_log.py diff --git a/Tools/fetch_file.py b/Tools/fetch_file.py new file mode 100644 index 000000000..7ad08192d --- /dev/null +++ b/Tools/fetch_file.py @@ -0,0 +1,207 @@ +#!/usr/bin/env python +############################################################################ +# +# Copyright (C) 2013-2014 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ + +"""Fetch files via nsh console + +Usage: python fetch_file.py [-l] [-f] [-d device] [-s speed] [-o out_path] path +\t-l\tList files +\t-f\tOverwrite existing files +\t-d\tSerial device +\t-s\tSerial baudrate +\t-o\tOutput path +\tpath\tPath to list/fetch, if ends with "/" then directory will be fetched recursively""" + +__author__ = "Anton Babushkin" +__version__ = "1.1" + +import serial, time, sys, os + +def _wait_for_string(ser, s, timeout): + t0 = time.time() + buf = [] + res = [] + while (True): + c = ser.read() + buf.append(c) + if len(buf) > len(s): + res.append(buf.pop(0)) + if "".join(buf) == s: + break + if timeout > 0.0 and time.time() - t0 > timeout: + raise Exception("Timeout while waiting for: " + s) + return "".join(res) + +def _exec_cmd(ser, cmd, timeout): + ser.write(cmd + "\n") + ser.flush() + _wait_for_string(ser, cmd + "\r\n", timeout) + return _wait_for_string(ser, "nsh> \x1b[K", timeout) + +def _ls_dir_raw(ser, dir, timeout): + return _exec_cmd(ser, "ls -l " + dir, timeout) + +def _ls_dir(ser, dir, timeout): + res = [] + for line in _ls_dir_raw(ser, dir, timeout).splitlines(): + if line == dir + ":": + continue + if line.startswith("nsh: ls: no such directory:"): + raise Exception("No such file: " + dir) + res.append((line[20:], int(line[11:19].strip()), line[1] == "d")) + return res + +def _get_file(ser, fn, fn_out, force, timeout): + print "Get %s:" % fn, + if not force: + # Check if file already exists with the same size + try: + os.stat(fn_out) + except: + pass + else: + print "already fetched, skip" + return + + cmd = "dumpfile " + fn + ser.write(cmd + "\n") + ser.flush() + _wait_for_string(ser, cmd + "\r\n", timeout) + res = _wait_for_string(ser, "\n", timeout) + if res.startswith("OK"): + # Got correct responce, open temp file + fn_out_part = fn_out + ".part" + fout = open(fn_out_part, "wb") + + size = int(res.split()[1]) + sys.stdout.write(" [%i bytes] " % size) + n = 0 + while (n < size): + buf = ser.read(min(size - n, 8192)) + n += len(buf) + sys.stdout.write(".") + sys.stdout.flush() + fout.write(buf) + print " done" + fout.close() + os.rename(fn_out_part, fn_out) + else: + raise Exception("Error reading file") + _wait_for_string(ser, "nsh> \x1b[K", timeout) + +def _get_files_in_dir(ser, path, path_out, force, timeout): + try: + os.mkdir(path_out) + except: + pass + for fn in _ls_dir(ser, path, timeout): + path_fn = os.path.join(path, fn[0]) + path_fn_out = os.path.join(path_out, fn[0]) + if fn[2]: + _get_files_in_dir(ser, path_fn[:-1], path_fn_out[:-1], force, timeout) + else: + _get_file(ser, path_fn, path_fn_out, force, timeout) + +def _usage(): + print """Usage: python fetch_file.py [-l] [-f] [-d device] [-s speed] [-o out_path] path +\t-l\tList files +\t-f\tOverwrite existing files +\t-d\tSerial device +\t-s\tSerial baudrate +\t-o\tOutput path +\tpath\tPath to list/fetch, if ends with "/" then directory will be fetched recursively""" + +def _main(): + dev = "/dev/tty.usbmodem1" + speed = "57600" + cmd = "get" + path = None + path_out = None + force = False + + opt = None + for arg in sys.argv[1:]: + if opt != None: + if opt == "d": + dev = arg + elif opt == "s": + speed = arg + elif opt == "o": + path_out = arg + opt = None + else: + if arg == "-l": + cmd = "ls" + elif arg == "-f": + force = True + elif arg == "-d": + opt = "d" + elif arg == "-s": + opt = "s" + elif arg == "-o": + opt = "o" + elif path == None: + path = arg + + if path == None: + _usage() + exit(0) + + # Connect to serial port + ser = serial.Serial(dev, speed, timeout=0.2) + + timeout = 1.0 + + try: + if cmd == "ls": + # List directory + print _ls_dir_raw(ser, path, timeout) + elif cmd == "get": + # Get file(s) + if path.endswith("/"): + # Get all files from directory recursively + if path_out == None: + path_out = os.path.split(path[:-1])[1] + _get_files_in_dir(ser, path[:-1], path_out, force, timeout) + else: + # Get one file + if path_out == None: + path_out = os.path.split(path)[1] + _get_file(ser, path, os.path.split(path)[1], force, timeout) + except Exception as e: + print e + + ser.close() + +if __name__ == "__main__": + _main() diff --git a/Tools/fetch_log.py b/Tools/fetch_log.py deleted file mode 100644 index edcc6557c..000000000 --- a/Tools/fetch_log.py +++ /dev/null @@ -1,133 +0,0 @@ -#!/usr/bin/env python -############################################################################ -# -# Copyright (C) 2012, 2013 PX4 Development Team. All rights reserved. -# -# Redistribution and use in source and binary forms, with or without -# modification, are permitted provided that the following conditions -# are met: -# -# 1. Redistributions of source code must retain the above copyright -# notice, this list of conditions and the following disclaimer. -# 2. Redistributions in binary form must reproduce the above copyright -# notice, this list of conditions and the following disclaimer in -# the documentation and/or other materials provided with the -# distribution. -# 3. Neither the name PX4 nor the names of its contributors may be -# used to endorse or promote products derived from this software -# without specific prior written permission. -# -# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS -# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT -# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS -# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE -# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, -# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, -# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS -# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED -# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT -# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN -# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -# POSSIBILITY OF SUCH DAMAGE. -# -############################################################################ - -# -# Log fetcher -# -# Print list of logs: -# python fetch_log.py -# -# Fetch log: -# python fetch_log.py sess001/log001.bin -# - -import serial, time, sys, os - -def wait_for_string(ser, s, timeout=1.0, debug=False): - t0 = time.time() - buf = [] - res = [] - n = 0 - while (True): - c = ser.read() - if debug: - sys.stderr.write(c) - buf.append(c) - if len(buf) > len(s): - res.append(buf.pop(0)) - n += 1 - if n % 10000 == 0: - sys.stderr.write(str(n) + "\n") - if "".join(buf) == s: - break - if timeout > 0.0 and time.time() - t0 > timeout: - raise Exception("Timeout while waiting for: " + s) - return "".join(res) - -def exec_cmd(ser, cmd, timeout): - ser.write(cmd + "\n") - ser.flush() - wait_for_string(ser, cmd + "\r\n", timeout) - return wait_for_string(ser, "nsh> \x1b[K", timeout) - -def ls_dir(ser, dir, timeout=1.0): - res = [] - for line in exec_cmd(ser, "ls -l " + dir, timeout).splitlines()[1:]: - res.append((line[20:], int(line[11:19].strip()), line[1] == "d")) - return res - -def list_logs(ser): - logs_dir = "/fs/microsd/log" - res = [] - for d in ls_dir(ser, logs_dir): - if d[2]: - sess_dir = d[0][:-1] - for f in ls_dir(ser, logs_dir + "/" + sess_dir): - log_file = f[0] - log_size = f[1] - res.append(sess_dir + "/" + log_file + "\t" + str(log_size)) - return "\n".join(res) - -def fetch_log(ser, fn, timeout): - cmd = "dumpfile " + fn - ser.write(cmd + "\n") - ser.flush() - wait_for_string(ser, cmd + "\r\n", timeout, True) - res = wait_for_string(ser, "\n", timeout, True) - data = [] - if res.startswith("OK"): - size = int(res.split()[1]) - n = 0 - print "Reading data:" - while (n < size): - buf = ser.read(min(size - n, 8192)) - data.append(buf) - n += len(buf) - sys.stdout.write(".") - sys.stdout.flush() - print - else: - raise Exception("Error reading log") - wait_for_string(ser, "nsh> \x1b[K", timeout) - return "".join(data) - -def main(): - dev = "/dev/tty.usbmodem1" - ser = serial.Serial(dev, "115200", timeout=0.2) - if len(sys.argv) < 2: - print list_logs(ser) - else: - log_file = sys.argv[1] - data = fetch_log(ser, "/fs/microsd/log/" + log_file, 1.0) - try: - os.mkdir(log_file.split("/")[0]) - except: - pass - fout = open(log_file, "wb") - fout.write(data) - fout.close() - ser.close() - -if __name__ == "__main__": - main() -- cgit v1.2.3 From 7f2799a78baf022db05484df2168b1b5a89923a9 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 17:49:51 +0200 Subject: global pos topic docs --- src/modules/uORB/topics/vehicle_global_position.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/uORB/topics/vehicle_global_position.h b/src/modules/uORB/topics/vehicle_global_position.h index e32529cb4..25137c1c6 100644 --- a/src/modules/uORB/topics/vehicle_global_position.h +++ b/src/modules/uORB/topics/vehicle_global_position.h @@ -70,8 +70,8 @@ struct vehicle_global_position_s { float vel_e; /**< Ground east velocity, m/s */ float vel_d; /**< Ground downside velocity, m/s */ float yaw; /**< Yaw in radians -PI..+PI. */ - float eph; - float epv; + float eph; /**< Standard deviation of position estimate horizontally */ + float epv; /**< Standard deviation of position vertically */ }; /** -- cgit v1.2.3 From 0cbd943d093f2cb69102e57ef7964b5dbebd9f86 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 17:50:52 +0200 Subject: Differentiate between EPH and EPV. Do not declare position invalid because of EPV (because we use the baro anyway). No fundamental logic change / cleanup to ensure current approach and arming logic remains intact --- src/modules/commander/commander.cpp | 29 +++++++++++++++-------------- 1 file changed, 15 insertions(+), 14 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 6c24734e5..dec5ab46c 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -163,7 +163,8 @@ static bool on_usb_power = false; static float takeoff_alt = 5.0f; static int parachute_enabled = 0; -static float eph_epv_threshold = 5.0f; +static float eph_threshold = 5.0f; +static float epv_threshold = 10.0f; static struct vehicle_status_s status; static struct actuator_armed_s armed; @@ -1108,32 +1109,32 @@ int commander_thread_main(int argc, char *argv[]) /* update condition_global_position_valid */ /* hysteresis for EPH/EPV */ - bool eph_epv_good; + bool eph_good; if (status.condition_global_position_valid) { - if (global_position.eph > eph_epv_threshold * 2.5f || global_position.epv > eph_epv_threshold * 2.5f) { - eph_epv_good = false; + if (global_position.eph > eph_threshold * 2.5f) { + eph_good = false; } else { - eph_epv_good = true; + eph_good = true; } } else { - if (global_position.eph < eph_epv_threshold && global_position.epv < eph_epv_threshold) { - eph_epv_good = true; + if (global_position.eph < eph_threshold) { + eph_good = true; } else { - eph_epv_good = false; + eph_good = false; } } - check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_epv_good, &(status.condition_global_position_valid), &status_changed); + check_valid(global_position.timestamp, POSITION_TIMEOUT, eph_good, &(status.condition_global_position_valid), &status_changed); /* check if GPS fix is ok */ /* update home position */ if (!status.condition_home_position_valid && status.condition_global_position_valid && !armed.armed && - (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) { + (global_position.eph < eph_threshold) && (global_position.epv < epv_threshold)) { home.lat = global_position.lat; home.lon = global_position.lon; @@ -1163,8 +1164,8 @@ int commander_thread_main(int argc, char *argv[]) /* hysteresis for EPH */ bool local_eph_good; - if (status.condition_global_position_valid) { - if (local_position.eph > eph_epv_threshold * 2.0f) { + if (status.condition_local_position_valid) { + if (local_position.eph > eph_threshold * 2.5f) { local_eph_good = false; } else { @@ -1172,7 +1173,7 @@ int commander_thread_main(int argc, char *argv[]) } } else { - if (local_position.eph < eph_epv_threshold) { + if (local_position.eph < eph_threshold) { local_eph_good = true; } else { @@ -1504,7 +1505,7 @@ int commander_thread_main(int argc, char *argv[]) /* update home position on arming if at least 2s from commander start spent to avoid setting home on in-air restart */ if (armed.armed && !was_armed && hrt_absolute_time() > start_time + 2000000 && status.condition_global_position_valid && - (global_position.eph < eph_epv_threshold) && (global_position.epv < eph_epv_threshold)) { + (global_position.eph < eph_threshold) && (global_position.epv < epv_threshold)) { // TODO remove code duplication home.lat = global_position.lat; -- cgit v1.2.3 From e3da7f564f1bc7746ba3be946fd02b95642cbf6e Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 29 Jul 2014 21:36:55 +0200 Subject: NaN check and better init in lowpass --- src/modules/controllib/blocks.cpp | 3 +++ src/modules/controllib/blocks.hpp | 2 +- 2 files changed, 4 insertions(+), 1 deletion(-) diff --git a/src/modules/controllib/blocks.cpp b/src/modules/controllib/blocks.cpp index 0175acda9..f739446fa 100644 --- a/src/modules/controllib/blocks.cpp +++ b/src/modules/controllib/blocks.cpp @@ -121,6 +121,9 @@ int blockLimitSymTest() float BlockLowPass::update(float input) { + if (!isfinite(getState())) { + setState(input); + } float b = 2 * float(M_PI) * getFCut() * getDt(); float a = b / (1 + b); setState(a * input + (1 - a)*getState()); diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp index 37d7832b3..bffc355a8 100644 --- a/src/modules/controllib/blocks.hpp +++ b/src/modules/controllib/blocks.hpp @@ -114,7 +114,7 @@ public: // methods BlockLowPass(SuperBlock *parent, const char *name) : Block(parent, name), - _state(0), + _state(0.0f/0.0f /* initialize to invalid val, force into is_finite() check on first call */), _fCut(this, "") // only one parameter, no need to name {}; virtual ~BlockLowPass() {}; -- cgit v1.2.3 From 1dc23d0c49d99fa93284a277a6bc4970ac0e7b3b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 30 Jul 2014 17:41:45 +0200 Subject: Disable mTECS until runtime error is better understood --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 56 +++++++++++----------- src/modules/fw_pos_control_l1/mtecs/mTecs.cpp | 1 + 2 files changed, 29 insertions(+), 28 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index f0e18d1bb..2d6c5c121 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -194,7 +194,7 @@ private: ECL_L1_Pos_Controller _l1_control; TECS _tecs; - fwPosctrl::mTecs _mTecs; + // fwPosctrl::mTecs _mTecs; bool _was_pos_control_mode; struct { @@ -443,7 +443,7 @@ FixedwingPositionControl::FixedwingPositionControl() : _groundspeed_undershoot(0.0f), _global_pos_valid(false), _l1_control(), - _mTecs(), + // _mTecs(), _was_pos_control_mode(false) { _nav_capabilities.turn_distance = 0.0f; @@ -603,7 +603,7 @@ FixedwingPositionControl::parameters_update() launchDetector.updateParams(); /* Update the mTecs */ - _mTecs.updateParams(); + // _mTecs.updateParams(); return OK; } @@ -820,9 +820,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2); math::Vector<3> accel_earth = _R_nb * accel_body; - if (!_mTecs.getEnabled()) { + // if (!_mTecs.getEnabled()) { _tecs.update_50hz(_global_pos.alt /* XXX might switch to alt err here */, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth); - } + // } /* define altitude error */ float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt; @@ -838,10 +838,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi if (!_was_pos_control_mode) { /* reset integrators */ - if (_mTecs.getEnabled()) { - _mTecs.resetIntegrators(); - _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s); - } + // if (_mTecs.getEnabled()) { + // _mTecs.resetIntegrators(); + // _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s); + // } } _was_pos_control_mode = true; @@ -1160,9 +1160,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi _att_sp.thrust = launchDetector.getThrottlePreTakeoff(); } else { - _att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() :_tecs.get_throttle_demand(), throttle_max); + _att_sp.thrust = math::min(/*_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() : */_tecs.get_throttle_demand(), throttle_max); } - _att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand(); + _att_sp.pitch_body = /*_mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : */_tecs.get_pitch_demand(); if (_control_mode.flag_control_position_enabled) { last_manual = false; @@ -1342,29 +1342,29 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_ const math::Vector<3> &ground_speed, tecs_mode mode) { - if (_mTecs.getEnabled()) { - /* Using mtecs library: prepare arguments for mtecs call */ - float flightPathAngle = 0.0f; - float ground_speed_length = ground_speed.length(); - if (ground_speed_length > FLT_EPSILON) { - flightPathAngle = -asinf(ground_speed(2)/ground_speed_length); - } - fwPosctrl::LimitOverride limitOverride; - if (climbout_mode) { - limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad); - } else { - limitOverride.disablePitchMinOverride(); - } - _mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode, - limitOverride); - } else { + // if (_mTecs.getEnabled()) { + // /* Using mtecs library: prepare arguments for mtecs call */ + // float flightPathAngle = 0.0f; + // float ground_speed_length = ground_speed.length(); + // if (ground_speed_length > FLT_EPSILON) { + // flightPathAngle = -asinf(ground_speed(2)/ground_speed_length); + // } + // fwPosctrl::LimitOverride limitOverride; + // if (climbout_mode) { + // limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad); + // } else { + // limitOverride.disablePitchMinOverride(); + // } + // _mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode, + // limitOverride); + // } else { /* Using tecs library */ _tecs.update_pitch_throttle(_R_nb, _att.pitch, altitude, alt_sp, v_sp, _airspeed.indicated_airspeed_m_s, eas2tas, climbout_mode, climbout_pitch_min_rad, throttle_min, throttle_max, throttle_cruise, pitch_min_rad, pitch_max_rad); - } + // } } int diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp index 749f57a2b..afc411a60 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp @@ -76,6 +76,7 @@ mTecs::mTecs() : _counter(0), _debug(false) { + warnx("starting"); } mTecs::~mTecs() -- cgit v1.2.3 From 39aa9112baf0120538255cf44292ff8e1ff3387c Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 30 Jul 2014 17:56:17 +0200 Subject: Fix threading in FW pos controller --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 87 +++++++++++----------- 1 file changed, 43 insertions(+), 44 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 2d6c5c121..eadb63f40 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -92,6 +92,8 @@ #include "landingslope.h" #include "mtecs/mTecs.h" +static int _control_task = -1; /**< task handle for sensor task */ + /** * L1 control app start / stop handling function @@ -116,9 +118,9 @@ public: /** * Start the sensors task. * - * @return OK on success. + * @return OK on success. */ - int start(); + static int start(); /** * Task status @@ -132,7 +134,6 @@ private: bool _task_should_exit; /**< if true, sensor task should exit */ bool _task_running; /**< if true, task is running in its mainloop */ - int _control_task; /**< task handle for sensor task */ int _global_pos_sub; int _pos_sp_triplet_sub; @@ -194,7 +195,7 @@ private: ECL_L1_Pos_Controller _l1_control; TECS _tecs; - // fwPosctrl::mTecs _mTecs; + fwPosctrl::mTecs _mTecs; bool _was_pos_control_mode; struct { @@ -393,7 +394,6 @@ FixedwingPositionControl::FixedwingPositionControl() : _mavlink_fd(-1), _task_should_exit(false), _task_running(false), - _control_task(-1), /* subscriptions */ _global_pos_sub(-1), @@ -443,7 +443,7 @@ FixedwingPositionControl::FixedwingPositionControl() : _groundspeed_undershoot(0.0f), _global_pos_valid(false), _l1_control(), - // _mTecs(), + _mTecs(), _was_pos_control_mode(false) { _nav_capabilities.turn_distance = 0.0f; @@ -603,7 +603,7 @@ FixedwingPositionControl::parameters_update() launchDetector.updateParams(); /* Update the mTecs */ - // _mTecs.updateParams(); + _mTecs.updateParams(); return OK; } @@ -704,7 +704,17 @@ FixedwingPositionControl::vehicle_setpoint_poll() void FixedwingPositionControl::task_main_trampoline(int argc, char *argv[]) { + l1_control::g_control = new FixedwingPositionControl(); + + if (l1_control::g_control == nullptr) { + warnx("OUT OF MEM"); + return; + } + + /* only returns on exit */ l1_control::g_control->task_main(); + delete l1_control::g_control; + l1_control::g_control = nullptr; } float @@ -820,9 +830,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi math::Vector<3> accel_body(_sensor_combined.accelerometer_m_s2); math::Vector<3> accel_earth = _R_nb * accel_body; - // if (!_mTecs.getEnabled()) { + if (!_mTecs.getEnabled()) { _tecs.update_50hz(_global_pos.alt /* XXX might switch to alt err here */, _airspeed.indicated_airspeed_m_s, _R_nb, accel_body, accel_earth); - // } + } /* define altitude error */ float altitude_error = _pos_sp_triplet.current.alt - _global_pos.alt; @@ -838,10 +848,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi if (!_was_pos_control_mode) { /* reset integrators */ - // if (_mTecs.getEnabled()) { - // _mTecs.resetIntegrators(); - // _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s); - // } + if (_mTecs.getEnabled()) { + _mTecs.resetIntegrators(); + _mTecs.resetDerivatives(_airspeed.true_airspeed_m_s); + } } _was_pos_control_mode = true; @@ -1160,9 +1170,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi _att_sp.thrust = launchDetector.getThrottlePreTakeoff(); } else { - _att_sp.thrust = math::min(/*_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() : */_tecs.get_throttle_demand(), throttle_max); + _att_sp.thrust = math::min(_mTecs.getEnabled() ? _mTecs.getThrottleSetpoint() : _tecs.get_throttle_demand(), throttle_max); } - _att_sp.pitch_body = /*_mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : */_tecs.get_pitch_demand(); + _att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand(); if (_control_mode.flag_control_position_enabled) { last_manual = false; @@ -1178,10 +1188,6 @@ void FixedwingPositionControl::task_main() { - /* inform about start */ - warnx("Initializing.."); - fflush(stdout); - /* * do subscriptions */ @@ -1342,29 +1348,29 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_ const math::Vector<3> &ground_speed, tecs_mode mode) { - // if (_mTecs.getEnabled()) { - // /* Using mtecs library: prepare arguments for mtecs call */ - // float flightPathAngle = 0.0f; - // float ground_speed_length = ground_speed.length(); - // if (ground_speed_length > FLT_EPSILON) { - // flightPathAngle = -asinf(ground_speed(2)/ground_speed_length); - // } - // fwPosctrl::LimitOverride limitOverride; - // if (climbout_mode) { - // limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad); - // } else { - // limitOverride.disablePitchMinOverride(); - // } - // _mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode, - // limitOverride); - // } else { + if (_mTecs.getEnabled()) { + /* Using mtecs library: prepare arguments for mtecs call */ + float flightPathAngle = 0.0f; + float ground_speed_length = ground_speed.length(); + if (ground_speed_length > FLT_EPSILON) { + flightPathAngle = -asinf(ground_speed(2)/ground_speed_length); + } + fwPosctrl::LimitOverride limitOverride; + if (climbout_mode) { + limitOverride.enablePitchMinOverride(M_RAD_TO_DEG_F * climbout_pitch_min_rad); + } else { + limitOverride.disablePitchMinOverride(); + } + _mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode, + limitOverride); + } else { /* Using tecs library */ _tecs.update_pitch_throttle(_R_nb, _att.pitch, altitude, alt_sp, v_sp, _airspeed.indicated_airspeed_m_s, eas2tas, climbout_mode, climbout_pitch_min_rad, throttle_min, throttle_max, throttle_cruise, pitch_min_rad, pitch_max_rad); - // } + } } int @@ -1398,14 +1404,7 @@ int fw_pos_control_l1_main(int argc, char *argv[]) if (l1_control::g_control != nullptr) errx(1, "already running"); - l1_control::g_control = new FixedwingPositionControl; - - if (l1_control::g_control == nullptr) - errx(1, "alloc failed"); - - if (OK != l1_control::g_control->start()) { - delete l1_control::g_control; - l1_control::g_control = nullptr; + if (OK != FixedwingPositionControl::start()) { err(1, "start failed"); } -- cgit v1.2.3 From 05e253b357caca3cdeb274027c7627a8a59d190d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 30 Jul 2014 19:49:01 +0200 Subject: Proper locking for message send calls --- src/modules/mavlink/mavlink_main.cpp | 22 ++++++++++++++++------ src/modules/mavlink/mavlink_main.h | 1 + 2 files changed, 17 insertions(+), 6 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 49781e8f8..8c79a1fee 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -159,9 +159,10 @@ Mavlink::Mavlink() : _rate_tx(0.0f), _rate_txerr(0.0f), _rate_rx(0.0f), - _rstatus {}, - _message_buffer {}, - _message_buffer_mutex {}, + _rstatus{}, + _message_buffer{}, + _message_buffer_mutex{}, + _send_mutex{}, _param_initialized(false), _param_system_id(0), _param_component_id(0), @@ -716,7 +717,7 @@ Mavlink::get_free_tx_buf() * flow control if it continues to be full */ int buf_free = 0; - (void) ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free); + (void) ioctl(_uart_fd, FIONWRITE, (unsigned long)&buf_free); if (get_flow_control_enabled() && buf_free < TX_BUFFER_GAP) { /* Disable hardware flow control: @@ -742,6 +743,8 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) return; } + pthread_mutex_lock(_send_mutex); + int buf_free = get_free_tx_buf(); uint8_t payload_len = mavlink_message_lengths[msgid]; @@ -754,7 +757,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) /* no enough space in buffer to send */ count_txerr(); count_txerrbytes(packet_len); - return; + goto out; } uint8_t buf[MAVLINK_MAX_PACKET_LEN]; @@ -762,7 +765,8 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) /* header */ buf[0] = MAVLINK_STX; buf[1] = payload_len; - buf[2] = mavlink_get_channel_status(_channel)->current_tx_seq++; // TODO use internal seq counter? + /* use mavlink's internal counter for the TX seq */ + buf[2] = mavlink_get_channel_status(_channel)->current_tx_seq++; buf[3] = mavlink_system.sysid; buf[4] = mavlink_system.compid; buf[5] = msgid; @@ -790,6 +794,9 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) _last_write_success_time = _last_write_try_time; count_txbytes(packet_len); } + +out: + pthread_mutex_unlock(_send_mutex); } void @@ -1298,6 +1305,9 @@ Mavlink::task_main(int argc, char *argv[]) return ERROR; } + /* initialize send mutex */ + pthread_mutex_init(&_send_mutex, NULL); + /* initialize mavlink text message buffering */ mavlink_logbuffer_init(&_logbuffer, 5); diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index 38149cf10..1e2e94cef 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -342,6 +342,7 @@ private: mavlink_message_buffer _message_buffer; pthread_mutex_t _message_buffer_mutex; + pthread_mutex_t _send_mutex; bool _param_initialized; param_t _param_system_id; -- cgit v1.2.3 From 5bad95c92dc7b974a793074ca173fe129d258fb7 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 30 Jul 2014 19:52:02 +0200 Subject: make GCC happy --- src/modules/mavlink/mavlink_main.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 8c79a1fee..618b9fa29 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -743,7 +743,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) return; } - pthread_mutex_lock(_send_mutex); + pthread_mutex_lock(&_send_mutex); int buf_free = get_free_tx_buf(); @@ -757,7 +757,8 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) /* no enough space in buffer to send */ count_txerr(); count_txerrbytes(packet_len); - goto out; + pthread_mutex_unlock(&_send_mutex); + return; } uint8_t buf[MAVLINK_MAX_PACKET_LEN]; @@ -795,8 +796,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) count_txbytes(packet_len); } -out: - pthread_mutex_unlock(_send_mutex); + pthread_mutex_unlock(&_send_mutex); } void -- cgit v1.2.3 From 391a5c82cbe6d02136e16528b472352e8461b02a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 30 Jul 2014 19:54:40 +0200 Subject: Print avionics voltage --- src/modules/commander/commander.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index daba4e740..409cf9d89 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -335,6 +335,7 @@ void print_status() { warnx("type: %s", (status.is_rotary_wing) ? "ROTARY" : "PLANE"); warnx("usb powered: %s", (on_usb_power) ? "yes" : "no"); + warnx("avionics rail: %6.2f V", (double)status.avionics_power_rail_voltage); /* read all relevant states */ int state_sub = orb_subscribe(ORB_ID(vehicle_status)); -- cgit v1.2.3 From edccc826a1834aa21171e2b5f88c97454955bb16 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 30 Jul 2014 21:16:29 +0200 Subject: Improved comment of bridge header --- src/modules/mavlink/mavlink_bridge_header.h | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_bridge_header.h b/src/modules/mavlink/mavlink_bridge_header.h index d82c2dae7..0cd08769e 100644 --- a/src/modules/mavlink/mavlink_bridge_header.h +++ b/src/modules/mavlink/mavlink_bridge_header.h @@ -44,7 +44,12 @@ __BEGIN_DECLS -//#define MAVLINK_USE_CONVENIENCE_FUNCTIONS +/* + * We are NOT using convenience functions, + * but instead send messages with a custom function. + * So we do NOT do this: + * #define MAVLINK_USE_CONVENIENCE_FUNCTIONS + */ /* use efficient approach, see mavlink_helpers.h */ #define MAVLINK_SEND_UART_BYTES mavlink_send_uart_bytes -- cgit v1.2.3 From fbbfe61d745202f7163d874ab61d4568f3a18a21 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 31 Jul 2014 10:49:28 +0200 Subject: Add missing lock --- src/modules/mavlink/mavlink_main.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 618b9fa29..84422c4aa 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -808,6 +808,8 @@ Mavlink::resend_message(mavlink_message_t *msg) return; } + pthread_mutex_lock(&_send_mutex); + int buf_free = get_free_tx_buf(); _last_write_try_time = hrt_absolute_time(); @@ -819,6 +821,7 @@ Mavlink::resend_message(mavlink_message_t *msg) /* no enough space in buffer to send */ count_txerr(); count_txerrbytes(packet_len); + pthread_mutex_unlock(&_send_mutex); return; } @@ -842,6 +845,8 @@ Mavlink::resend_message(mavlink_message_t *msg) _last_write_success_time = _last_write_try_time; count_txbytes(packet_len); } + + pthread_mutex_unlock(&_send_mutex); } void -- cgit v1.2.3 From 9d7e3feffcfb34708cda5a726b7900101f41b205 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 31 Jul 2014 11:18:59 +0200 Subject: airspeed: Filter slightly more, just a touch to not induce phase delay --- src/drivers/meas_airspeed/meas_airspeed.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/meas_airspeed/meas_airspeed.cpp b/src/drivers/meas_airspeed/meas_airspeed.cpp index 9cfa7f383..159706278 100644 --- a/src/drivers/meas_airspeed/meas_airspeed.cpp +++ b/src/drivers/meas_airspeed/meas_airspeed.cpp @@ -103,7 +103,7 @@ /* Measurement rate is 100Hz */ #define MEAS_RATE 100 -#define MEAS_DRIVER_FILTER_FREQ 1.5f +#define MEAS_DRIVER_FILTER_FREQ 1.2f #define CONVERSION_INTERVAL (1000000 / MEAS_RATE) /* microseconds */ class MEASAirspeed : public Airspeed -- cgit v1.2.3 From 2b71067618b2b4333c44072e27b960435407166d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 31 Jul 2014 11:28:17 +0200 Subject: Code style fixes --- src/modules/mavlink/mavlink_main.cpp | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 84422c4aa..5589738c1 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -159,10 +159,10 @@ Mavlink::Mavlink() : _rate_tx(0.0f), _rate_txerr(0.0f), _rate_rx(0.0f), - _rstatus{}, - _message_buffer{}, - _message_buffer_mutex{}, - _send_mutex{}, + _rstatus {}, + _message_buffer {}, + _message_buffer_mutex {}, + _send_mutex {}, _param_initialized(false), _param_system_id(0), _param_component_id(0), @@ -387,7 +387,7 @@ Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self) /* if not in normal mode, we are an onboard link * onboard links should only pass on messages from the same system ID */ - if(!(self->_mode != MAVLINK_MODE_NORMAL && msg->sysid != mavlink_system.sysid)) { + if (!(self->_mode != MAVLINK_MODE_NORMAL && msg->sysid != mavlink_system.sysid)) { inst->pass_message(msg); } } @@ -731,6 +731,7 @@ Mavlink::get_free_tx_buf() enable_flow_control(false); } } + return buf_free; } @@ -778,7 +779,7 @@ Mavlink::send_message(const uint8_t msgid, const void *msg) /* checksum */ uint16_t checksum; crc_init(&checksum); - crc_accumulate_buffer(&checksum, (const char*) &buf[1], MAVLINK_CORE_HEADER_LEN + payload_len); + crc_accumulate_buffer(&checksum, (const char *) &buf[1], MAVLINK_CORE_HEADER_LEN + payload_len); crc_accumulate(mavlink_message_crcs[msgid], &checksum); buf[MAVLINK_NUM_HEADER_BYTES + payload_len] = (uint8_t)(checksum & 0xFF); @@ -985,7 +986,7 @@ Mavlink::adjust_stream_rates(const float multiplier) /* allow max ~600 Hz */ if (interval < 1600) { interval = 1600; - } + } /* set new interval */ stream->set_interval(interval * multiplier); @@ -1513,6 +1514,7 @@ Mavlink::task_main(int argc, char *argv[]) _bytes_txerr = 0; _bytes_rx = 0; } + _bytes_timestamp = t; } @@ -1676,6 +1678,7 @@ Mavlink::display_status() } else { printf("\tno telem status.\n"); } + printf("\trates:\n"); printf("\ttx: %.3f kB/s\n", (double)_rate_tx); printf("\ttxerr: %.3f kB/s\n", (double)_rate_txerr); -- cgit v1.2.3 From 39699670026f463df79a45c0dbf5cf7ceea8d5a1 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 31 Jul 2014 12:16:11 +0200 Subject: Default to TECS --- src/modules/fw_pos_control_l1/mtecs/mTecs_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c index 7cfe63fbc..58a1e9f6b 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs_params.c @@ -55,7 +55,7 @@ * @max 1 * @group mTECS */ -PARAM_DEFINE_INT32(MT_ENABLED, 1); +PARAM_DEFINE_INT32(MT_ENABLED, 0); /** * Total Energy Rate Control Feedforward -- cgit v1.2.3 From 92a4757971701bc1536db85f62590f9e864d96fe Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 31 Jul 2014 12:45:44 +0200 Subject: sdlog2_dump.py: minor fix allowing handling FMT messages in the middle of stream --- Tools/sdlog2/sdlog2_dump.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/Tools/sdlog2/sdlog2_dump.py b/Tools/sdlog2/sdlog2_dump.py index 5b1e55e22..ca2efb021 100644 --- a/Tools/sdlog2/sdlog2_dump.py +++ b/Tools/sdlog2/sdlog2_dump.py @@ -149,7 +149,8 @@ class SDLog2Parser: break if first_data_msg: # build CSV columns and init data map - self.__initCSV() + if not self.__debug_out: + self.__initCSV() first_data_msg = False self.__parseMsg(msg_descr) bytes_read += self.__ptr -- cgit v1.2.3 From fc2e0fad4731ef543be4c3da73de6b670d40d804 Mon Sep 17 00:00:00 2001 From: philipoe Date: Thu, 31 Jul 2014 15:23:30 +0200 Subject: TECS: Added separate gain / time constant for the throttle loop to allow independent tuning --- src/lib/external_lgpl/tecs/tecs.cpp | 2 +- src/lib/external_lgpl/tecs/tecs.h | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp index 6386e37a0..16c7e5ffa 100644 --- a/src/lib/external_lgpl/tecs/tecs.cpp +++ b/src/lib/external_lgpl/tecs/tecs.cpp @@ -298,7 +298,7 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM } else { // Calculate gain scaler from specific energy error to throttle - float K_STE2Thr = 1 / (_timeConst * (_STEdot_max - _STEdot_min)); + float K_STE2Thr = 1 / (_timeConstThrot * (_STEdot_max - _STEdot_min)); // Calculate feed-forward throttle float ff_throttle = 0; diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h index 5cafb1c79..10c9e9344 100644 --- a/src/lib/external_lgpl/tecs/tecs.h +++ b/src/lib/external_lgpl/tecs/tecs.h @@ -123,6 +123,10 @@ public: _timeConst = time_const; } + void set_time_const_throt(float time_const_throt) { + _timeConstThrot = time_const_throt; + } + void set_min_sink_rate(float rate) { _minSinkRate = rate; } @@ -204,6 +208,7 @@ private: float _minSinkRate; float _maxSinkRate; float _timeConst; + float _timeConstThrot; float _ptchDamp; float _thrDamp; float _integGain; -- cgit v1.2.3 From 7f293be7d77603768899aedb438821dd19b8b4d7 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 31 Jul 2014 17:30:00 +0200 Subject: mavlink, rc.usb: increase HIL_CONTROLS rate and datarate on USB to allow HIL simulation @ 200Hz --- ROMFS/px4fmu_common/init.d/rc.usb | 2 +- src/modules/mavlink/mavlink_main.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rc.usb b/ROMFS/px4fmu_common/init.d/rc.usb index eb6039b4c..f1c21f295 100644 --- a/ROMFS/px4fmu_common/init.d/rc.usb +++ b/ROMFS/px4fmu_common/init.d/rc.usb @@ -3,7 +3,7 @@ # USB MAVLink start # -mavlink start -r 10000 -d /dev/ttyACM0 -x +mavlink start -r 20000 -d /dev/ttyACM0 -x # Enable a number of interesting streams we want via USB mavlink stream -d /dev/ttyACM0 -s PARAM_VALUE -r 200 usleep 100000 diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 5589738c1..9a39d3bed 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -90,7 +90,7 @@ static const int ERROR = -1; #define DEFAULT_DEVICE_NAME "/dev/ttyS1" -#define MAX_DATA_RATE 10000 // max data rate in bytes/s +#define MAX_DATA_RATE 20000 // max data rate in bytes/s #define MAIN_LOOP_DELAY 10000 // 100 Hz @ 1000 bytes/s data rate #define TX_BUFFER_GAP MAVLINK_MAX_PACKET_LEN @@ -694,7 +694,7 @@ Mavlink::set_hil_enabled(bool hil_enabled) /* enable HIL */ if (hil_enabled && !_hil_enabled) { _hil_enabled = true; - configure_stream("HIL_CONTROLS", 150.0f); + configure_stream("HIL_CONTROLS", 200.0f); } /* disable HIL */ -- cgit v1.2.3 From b8c14417ce5c667920b32e3ba94ca8f496e0d10c Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Thu, 31 Jul 2014 23:34:34 +0400 Subject: UAVCAN update --- uavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/uavcan b/uavcan index d84fc8a84..6980ee824 160000 --- a/uavcan +++ b/uavcan @@ -1 +1 @@ -Subproject commit d84fc8a84678d93f97f93b240c81472797ca5889 +Subproject commit 6980ee824074aa2f7a62221bf6040ee411119520 -- cgit v1.2.3 From 87273abc9aa0006baff53741e605c9992ec8c955 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 1 Aug 2014 00:56:44 +0400 Subject: UAVCAN node version info --- src/modules/uavcan/uavcan_main.cpp | 61 +++++++++++++++++++++++++++++--------- src/modules/uavcan/uavcan_main.hpp | 1 + 2 files changed, 48 insertions(+), 14 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 27e77e9c5..ffd599070 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -39,6 +39,8 @@ #include #include #include +#include +#include #include #include @@ -173,6 +175,44 @@ int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate) return OK; } +void UavcanNode::fill_node_info() +{ + /* software version */ + uavcan::protocol::SoftwareVersion swver; + + // Extracting the last 8 hex digits of FW_GIT and converting them to int + const unsigned fw_git_len = std::strlen(FW_GIT); + if (fw_git_len >= 8) { + char fw_git_short[9] = {}; + std::memmove(fw_git_short, FW_GIT + fw_git_len - 8, 8); + assert(fw_git_short[8] == '\0'); + char *end = nullptr; + swver.vcs_commit = std::strtol(fw_git_short, &end, 16); + swver.optional_field_mask |= swver.OPTIONAL_FIELD_MASK_VCS_COMMIT; + } + + warnx("SW version vcs_commit: 0x%08x", unsigned(swver.vcs_commit)); + + _node.setSoftwareVersion(swver); + + /* hardware version */ + uavcan::protocol::HardwareVersion hwver; + + if (!std::strncmp(HW_ARCH, "PX4FMU_V1", 9)) { + hwver.major = 1; + } else if (!std::strncmp(HW_ARCH, "PX4FMU_V2", 9)) { + hwver.major = 2; + } else { + ; // All other values of HW_ARCH resolve to zero + } + + uint8_t udid[12] = {}; // Someone seems to love magic numbers + get_board_serial(udid); + uavcan::copy(udid, udid + sizeof(udid), hwver.unique_id.begin()); + + _node.setHardwareVersion(hwver); +} + int UavcanNode::init(uavcan::NodeID node_id) { int ret = -1; @@ -183,6 +223,13 @@ int UavcanNode::init(uavcan::NodeID node_id) if (ret != OK) return ret; + _node.setName("org.pixhawk.pixhawk"); + + _node.setNodeID(node_id); + + fill_node_info(); + + /* initializing the bridges UAVCAN <--> uORB */ ret = _esc_controller.init(); if (ret < 0) return ret; @@ -191,20 +238,6 @@ int UavcanNode::init(uavcan::NodeID node_id) if (ret < 0) return ret; - uavcan::protocol::SoftwareVersion swver; - swver.major = 12; // TODO fill version info - swver.minor = 34; - _node.setSoftwareVersion(swver); - - uavcan::protocol::HardwareVersion hwver; - hwver.major = 42; // TODO fill version info - hwver.minor = 42; - _node.setHardwareVersion(hwver); - - _node.setName("org.pixhawk"); // Huh? - - _node.setNodeID(node_id); - return _node.start(); } diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp index 443525379..05b66fd7b 100644 --- a/src/modules/uavcan/uavcan_main.hpp +++ b/src/modules/uavcan/uavcan_main.hpp @@ -94,6 +94,7 @@ public: static UavcanNode* instance() { return _instance; } private: + void fill_node_info(); int init(uavcan::NodeID node_id); void node_spin_once(); int run(); -- cgit v1.2.3 From b606674fc77aa772fba66ad09dd3879a62a7f44c Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Fri, 1 Aug 2014 01:04:24 +0400 Subject: Removed misleading comment from the UAVCAN module makefile --- src/modules/uavcan/module.mk | 4 ---- 1 file changed, 4 deletions(-) diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk index 1ef6f0cfa..3865f2468 100644 --- a/src/modules/uavcan/module.mk +++ b/src/modules/uavcan/module.mk @@ -65,10 +65,6 @@ override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM # # Invoke DSDL compiler -# TODO: Add make target for this, or invoke dsdlc manually. -# The second option assumes that the generated headers shall be saved -# under the version control, which may be undesirable. -# The first option requires any Python and the Python Mako library for the sources to be built. # $(info $(shell $(LIBUAVCAN_DSDLC) $(UAVCAN_DSDL_DIR))) INCLUDE_DIRS += dsdlc_generated -- cgit v1.2.3 From 2d4dd0d5c03a7ef3d696f40b6a6988e08e991034 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 28 Jul 2014 20:37:26 +0900 Subject: Tone alarm sound for barometer check fail --- src/drivers/drv_tone_alarm.h | 1 + src/drivers/stm32/tone_alarm/tone_alarm.cpp | 2 ++ 2 files changed, 3 insertions(+) diff --git a/src/drivers/drv_tone_alarm.h b/src/drivers/drv_tone_alarm.h index 19f792d19..307f7dbc7 100644 --- a/src/drivers/drv_tone_alarm.h +++ b/src/drivers/drv_tone_alarm.h @@ -150,6 +150,7 @@ enum { TONE_ARMING_FAILURE_TUNE, TONE_PARACHUTE_RELEASE_TUNE, TONE_EKF_WARNING_TUNE, + TONE_BARO_WARNING_TUNE, TONE_NUMBER_OF_TUNES }; diff --git a/src/drivers/stm32/tone_alarm/tone_alarm.cpp b/src/drivers/stm32/tone_alarm/tone_alarm.cpp index 03c7bd399..8f523b390 100644 --- a/src/drivers/stm32/tone_alarm/tone_alarm.cpp +++ b/src/drivers/stm32/tone_alarm/tone_alarm.cpp @@ -337,6 +337,7 @@ ToneAlarm::ToneAlarm() : _default_tunes[TONE_ARMING_FAILURE_TUNE] = "MFT255L4<< Date: Fri, 1 Aug 2014 13:04:28 +0200 Subject: Move the last throttle demand setting to a better position --- src/lib/external_lgpl/tecs/tecs.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp index 16c7e5ffa..579fb5d42 100644 --- a/src/lib/external_lgpl/tecs/tecs.cpp +++ b/src/lib/external_lgpl/tecs/tecs.cpp @@ -327,9 +327,12 @@ void TECS::_update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotM _throttle_dem = constrain(_throttle_dem, _last_throttle_dem - thrRateIncr, _last_throttle_dem + thrRateIncr); - _last_throttle_dem = _throttle_dem; } + // Ensure _last_throttle_dem is always initialized properly + // Also: The throttle_slewrate limit is only applied to throttle_dem, but does not limit the integrator!! + _last_throttle_dem = _throttle_dem; + // Calculate integrator state upper and lower limits // Set to a value thqat will allow 0.1 (10%) throttle saturation to allow for noise on the demand -- cgit v1.2.3 From 3b1c92e42f57277a12d40963c22fbea9820ee0ad Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 1 Aug 2014 13:10:07 +0200 Subject: Make throttle time constant tunable separately, group TECS params correctly, make climbout alt configurable --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 11 ++++- .../fw_pos_control_l1/fw_pos_control_l1_params.c | 49 ++++++++++++++++------ 2 files changed, 46 insertions(+), 14 deletions(-) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index eadb63f40..f05f20cd0 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -203,9 +203,11 @@ private: float l1_damping; float time_const; + float time_const_throt; float min_sink_rate; float max_sink_rate; float max_climb_rate; + float climbout_diff; float heightrate_p; float speedrate_p; float throttle_damp; @@ -245,9 +247,11 @@ private: param_t l1_damping; param_t time_const; + param_t time_const_throt; param_t min_sink_rate; param_t max_sink_rate; param_t max_climb_rate; + param_t climbout_diff; param_t heightrate_p; param_t speedrate_p; param_t throttle_damp; @@ -471,9 +475,11 @@ FixedwingPositionControl::FixedwingPositionControl() : _parameter_handles.range_finder_rel_alt = param_find("FW_LND_RFRALT"); _parameter_handles.time_const = param_find("FW_T_TIME_CONST"); + _parameter_handles.time_const_throt = param_find("FW_T_THRO_CONST"); _parameter_handles.min_sink_rate = param_find("FW_T_SINK_MIN"); _parameter_handles.max_sink_rate = param_find("FW_T_SINK_MAX"); _parameter_handles.max_climb_rate = param_find("FW_T_CLMB_MAX"); + _parameter_handles.climbout_diff = param_find("FW_CLMBOUT_DIFF"); _parameter_handles.throttle_damp = param_find("FW_T_THR_DAMP"); _parameter_handles.integrator_gain = param_find("FW_T_INTEG_GAIN"); _parameter_handles.vertical_accel_limit = param_find("FW_T_VERT_ACC"); @@ -536,6 +542,7 @@ FixedwingPositionControl::parameters_update() param_get(_parameter_handles.throttle_land_max, &(_parameters.throttle_land_max)); param_get(_parameter_handles.time_const, &(_parameters.time_const)); + param_get(_parameter_handles.time_const_throt, &(_parameters.time_const_throt)); param_get(_parameter_handles.min_sink_rate, &(_parameters.min_sink_rate)); param_get(_parameter_handles.max_sink_rate, &(_parameters.max_sink_rate)); param_get(_parameter_handles.throttle_damp, &(_parameters.throttle_damp)); @@ -547,6 +554,7 @@ FixedwingPositionControl::parameters_update() param_get(_parameter_handles.speed_weight, &(_parameters.speed_weight)); param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping)); param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate)); + param_get(_parameter_handles.climbout_diff, &(_parameters.climbout_diff)); param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p)); param_get(_parameter_handles.speedrate_p, &(_parameters.speedrate_p)); @@ -564,6 +572,7 @@ FixedwingPositionControl::parameters_update() _l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit)); _tecs.set_time_const(_parameters.time_const); + _tecs.set_time_const_throt(_parameters.time_const_throt); _tecs.set_min_sink_rate(_parameters.min_sink_rate); _tecs.set_max_sink_rate(_parameters.max_sink_rate); _tecs.set_throttle_damp(_parameters.throttle_damp); @@ -1095,7 +1104,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi usePreTakeoffThrust = false; /* apply minimum pitch and limit roll if target altitude is not within 10 meters */ - if (altitude_error > 15.0f) { + if (_parameters.climbout_diff > 0.001f && altitude_error > _parameters.climbout_diff) { /* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */ tecs_update_pitch_throttle(_pos_sp_triplet.current.alt, diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index 52128e1b7..a0d9309b9 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -154,6 +154,18 @@ PARAM_DEFINE_FLOAT(FW_THR_MIN, 0.0f); */ PARAM_DEFINE_FLOAT(FW_THR_LND_MAX, 1.0f); +/** + * Climbout Altitude difference + * + * If the altitude error exceeds this parameter, the system will climb out + * with maximum throttle and minimum airspeed until it is closer than this + * distance to the desired altitude. Mostly used for takeoff waypoints / modes. + * Set to zero to disable climbout mode (not recommended). + * + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_CLMBOUT_DIFF, 25.0f); + /** * Maximum climb rate * @@ -181,7 +193,7 @@ PARAM_DEFINE_FLOAT(FW_T_CLMB_MAX, 5.0f); * set to THR_MIN and flown at the same airspeed as used * to measure FW_T_CLMB_MAX. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); @@ -194,7 +206,7 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MIN, 2.0f); * exceeding the lower pitch angle limit and without over-speeding * the aircraft. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); @@ -205,17 +217,28 @@ PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f); * Smaller values make it faster to respond, larger values make it slower * to respond. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_TIME_CONST, 5.0f); +/** + * TECS Throttle time constant + * + * This is the time constant of the TECS throttle control algorithm (in seconds). + * Smaller values make it faster to respond, larger values make it slower + * to respond. + * + * @group Fixed Wing TECS + */ +PARAM_DEFINE_FLOAT(FW_T_THRO_CONST, 8.0f); + /** * Throttle damping factor * * This is the damping gain for the throttle demand loop. * Increase to add damping to correct for oscillations in speed and height. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f); @@ -227,7 +250,7 @@ PARAM_DEFINE_FLOAT(FW_T_THR_DAMP, 0.5f); * and height offsets are trimmed out, but reduces damping and * increases overshoot. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); @@ -240,7 +263,7 @@ PARAM_DEFINE_FLOAT(FW_T_INTEG_GAIN, 0.1f); * allows for reasonably aggressive pitch changes if required to recover * from under-speed conditions. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); @@ -253,7 +276,7 @@ PARAM_DEFINE_FLOAT(FW_T_VERT_ACC, 7.0f); * the solution more towards use of the barometer, whilst reducing it weights * the solution more towards use of the accelerometer data. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f); @@ -266,7 +289,7 @@ PARAM_DEFINE_FLOAT(FW_T_HGT_OMEGA, 3.0f); * more towards use of the arispeed sensor, whilst reducing it weights the * solution more towards use of the accelerometer data. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); @@ -282,7 +305,7 @@ PARAM_DEFINE_FLOAT(FW_T_SPD_OMEGA, 2.0f); * aircraft (eg powered sailplanes) can use a lower value, whereas * inefficient low aspect-ratio models (eg delta wings) can use a higher value. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f); @@ -300,7 +323,7 @@ PARAM_DEFINE_FLOAT(FW_T_RLL2THR, 10.0f); * Note to Glider Pilots - set this parameter to 2.0 (The glider will * adjust its pitch angle to maintain airspeed, ignoring changes in height). * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); @@ -312,21 +335,21 @@ PARAM_DEFINE_FLOAT(FW_T_SPDWEIGHT, 1.0f); * will work well provided the pitch to servo controller has been tuned * properly. * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f); /** * Height rate P factor * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f); /** * Speed rate P factor * - * @group L1 Control + * @group Fixed Wing TECS */ PARAM_DEFINE_FLOAT(FW_T_SRATE_P, 0.05f); -- cgit v1.2.3 From 2e4dff3fea2177538f3549cedd8f84fbbbecd4ad Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 1 Aug 2014 13:21:30 +0200 Subject: removed debug statement from mTECS --- src/modules/fw_pos_control_l1/mtecs/mTecs.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp index afc411a60..749f57a2b 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp @@ -76,7 +76,6 @@ mTecs::mTecs() : _counter(0), _debug(false) { - warnx("starting"); } mTecs::~mTecs() -- cgit v1.2.3 From 32e32d92bdad3eb4e92e9e53c112fcdcf848c7e6 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 1 Aug 2014 14:39:24 +0200 Subject: Add throttle slew rate param --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 5 +++++ src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c | 11 +++++++++++ 2 files changed, 16 insertions(+) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index f05f20cd0..189a19d48 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -229,6 +229,7 @@ private: float throttle_min; float throttle_max; float throttle_cruise; + float throttle_slew_max; float throttle_land_max; @@ -273,6 +274,7 @@ private: param_t throttle_min; param_t throttle_max; param_t throttle_cruise; + param_t throttle_slew_max; param_t throttle_land_max; @@ -464,6 +466,7 @@ FixedwingPositionControl::FixedwingPositionControl() : _parameter_handles.roll_limit = param_find("FW_R_LIM"); _parameter_handles.throttle_min = param_find("FW_THR_MIN"); _parameter_handles.throttle_max = param_find("FW_THR_MAX"); + _parameter_handles.throttle_slew_max = param_find("FW_THR_SLEW_MAX"); _parameter_handles.throttle_cruise = param_find("FW_THR_CRUISE"); _parameter_handles.throttle_land_max = param_find("FW_THR_LND_MAX"); @@ -538,6 +541,7 @@ FixedwingPositionControl::parameters_update() param_get(_parameter_handles.throttle_min, &(_parameters.throttle_min)); param_get(_parameter_handles.throttle_max, &(_parameters.throttle_max)); param_get(_parameter_handles.throttle_cruise, &(_parameters.throttle_cruise)); + param_get(_parameter_handles.throttle_slew_max, &(_parameters.throttle_slew_max)); param_get(_parameter_handles.throttle_land_max, &(_parameters.throttle_land_max)); @@ -576,6 +580,7 @@ FixedwingPositionControl::parameters_update() _tecs.set_min_sink_rate(_parameters.min_sink_rate); _tecs.set_max_sink_rate(_parameters.max_sink_rate); _tecs.set_throttle_damp(_parameters.throttle_damp); + _tecs.set_throttle_slewrate(_parameters.throttle_slew_max); _tecs.set_integrator_gain(_parameters.integrator_gain); _tecs.set_vertical_accel_limit(_parameters.vertical_accel_limit); _tecs.set_height_comp_filter_omega(_parameters.height_comp_filter_omega); diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c index a0d9309b9..41c374407 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c @@ -82,6 +82,17 @@ PARAM_DEFINE_FLOAT(FW_L1_DAMPING, 0.75f); */ PARAM_DEFINE_FLOAT(FW_THR_CRUISE, 0.7f); +/** + * Throttle max slew rate + * + * Maximum slew rate for the commanded throttle + * + * @min 0.0 + * @max 1.0 + * @group L1 Control + */ +PARAM_DEFINE_FLOAT(FW_THR_SLEW_MAX, 0.0f); + /** * Negative pitch limit * -- cgit v1.2.3 From 491c6c29acef343819f32655e6e87334531af8cf Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 1 Aug 2014 14:43:56 +0200 Subject: Init values --- src/lib/external_lgpl/tecs/tecs.h | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h index 10c9e9344..752b0ddd9 100644 --- a/src/lib/external_lgpl/tecs/tecs.h +++ b/src/lib/external_lgpl/tecs/tecs.h @@ -28,6 +28,26 @@ class __EXPORT TECS { public: TECS() : + _update_50hz_last_usec(0), + _update_speed_last_usec(0), + _update_pitch_throttle_last_usec(0), + // TECS tuning parameters + _hgtCompFiltOmega(0.0f), + _spdCompFiltOmega(0.0f), + _maxClimbRate(2.0f), + _minSinkRate(1.0f), + _maxSinkRate(2.0f), + _timeConst(5.0f), + _timeConstThrot(8.0f), + _ptchDamp(0.0f), + _thrDamp(0.0f), + _integGain(0.0f), + _vertAccLim(0.0f), + _rollComp(0.0f), + _spdWeight(0.5f), + _heightrate_p(0.0f), + _speedrate_p(0.0f), + _throttle_dem(0.0f), _pitch_dem(0.0f), _integ1_state(0.0f), _integ2_state(0.0f), -- cgit v1.2.3 From c3666a5504fc89b7e1861e25c9b6cb0c07453784 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 1 Aug 2014 23:18:43 +0200 Subject: Widen default first WP radius --- src/modules/navigator/mission_params.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/navigator/mission_params.c b/src/modules/navigator/mission_params.c index 881caa24e..d15e1e771 100644 --- a/src/modules/navigator/mission_params.c +++ b/src/modules/navigator/mission_params.c @@ -78,7 +78,7 @@ PARAM_DEFINE_INT32(MIS_ONBOARD_EN, 1); * waypoint is more distant than MIS_DIS_1WP from the current position. * * @min 0 - * @max 250 + * @max 1000 * @group Mission */ -PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 175); +PARAM_DEFINE_FLOAT(MIS_DIST_1WP, 500); -- cgit v1.2.3 From 4d03202c4c8c322f9d93da0051dca015ab473cde Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 1 Aug 2014 23:42:26 +0200 Subject: Warn on far waypoints --- src/modules/navigator/mission.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index 12f6b9c21..c0e37a3ed 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -273,6 +273,10 @@ Mission::check_dist_1wp() if (dist_to_1wp < _param_dist_1wp.get()) { _dist_1wp_ok = true; + if (dist_to_1wp > ((_param_dist_1wp.get() * 3) / 2)) { + /* allow at 2/3 distance, but warn */ + mavlink_log_critical(_navigator->get_mavlink_fd(), "Warning: First waypoint very far: %d m", (int)dist_to_1wp); + } return true; } else { -- cgit v1.2.3 From 9725a1635254ba6c0c1df0413f94398ec28e23f9 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Sat, 2 Aug 2014 03:34:57 +0400 Subject: UAVCAN: Fixed short git hash computation --- src/modules/uavcan/uavcan_main.cpp | 17 +++++++---------- 1 file changed, 7 insertions(+), 10 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index ffd599070..9d5404baf 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -180,16 +180,13 @@ void UavcanNode::fill_node_info() /* software version */ uavcan::protocol::SoftwareVersion swver; - // Extracting the last 8 hex digits of FW_GIT and converting them to int - const unsigned fw_git_len = std::strlen(FW_GIT); - if (fw_git_len >= 8) { - char fw_git_short[9] = {}; - std::memmove(fw_git_short, FW_GIT + fw_git_len - 8, 8); - assert(fw_git_short[8] == '\0'); - char *end = nullptr; - swver.vcs_commit = std::strtol(fw_git_short, &end, 16); - swver.optional_field_mask |= swver.OPTIONAL_FIELD_MASK_VCS_COMMIT; - } + // Extracting the first 8 hex digits of FW_GIT and converting them to int + char fw_git_short[9] = {}; + std::memmove(fw_git_short, FW_GIT, 8); + assert(fw_git_short[8] == '\0'); + char *end = nullptr; + swver.vcs_commit = std::strtol(fw_git_short, &end, 16); + swver.optional_field_mask |= swver.OPTIONAL_FIELD_MASK_VCS_COMMIT; warnx("SW version vcs_commit: 0x%08x", unsigned(swver.vcs_commit)); -- cgit v1.2.3 From 5824607c76ed38b5c08d1c9031814f741bce7c8b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Sat, 2 Aug 2014 13:01:42 +0200 Subject: uavcan: fix actuator groups subcriptions and poll() --- src/modules/uavcan/uavcan_main.cpp | 36 +++++++++++++++++++----------------- 1 file changed, 19 insertions(+), 17 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 9d5404baf..5b1539e3e 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -253,7 +253,6 @@ int UavcanNode::run() // XXX figure out the output count _output_count = 2; - _armed_sub = orb_subscribe(ORB_ID(actuator_armed)); actuator_outputs_s outputs; @@ -273,21 +272,23 @@ int UavcanNode::run() _node.setStatusOk(); - while (!_task_should_exit) { + /* + * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error). + * Please note that with such multiplexing it is no longer possible to rely only on + * the value returned from poll() to detect whether actuator control has timed out or not. + * Instead, all ORB events need to be checked individually (see below). + */ + _poll_fds_num = 0; + _poll_fds[_poll_fds_num] = ::pollfd(); + _poll_fds[_poll_fds_num].fd = busevent_fd; + _poll_fds[_poll_fds_num].events = POLLIN; + _poll_fds_num += 1; + while (!_task_should_exit) { + // update actuator controls subscriptions if needed if (_groups_subscribed != _groups_required) { subscribe(); _groups_subscribed = _groups_required; - /* - * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error). - * Please note that with such multiplexing it is no longer possible to rely only on - * the value returned from poll() to detect whether actuator control has timed out or not. - * Instead, all ORB events need to be checked individually (see below). - */ - _poll_fds[_poll_fds_num] = ::pollfd(); - _poll_fds[_poll_fds_num].fd = busevent_fd; - _poll_fds[_poll_fds_num].events = POLLIN; - _poll_fds_num += 1; } const int poll_ret = ::poll(_poll_fds, _poll_fds_num, PollTimeoutMs); @@ -301,7 +302,7 @@ int UavcanNode::run() } else { // get controls for required topics bool controls_updated = false; - unsigned poll_id = 0; + unsigned poll_id = 1; for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (_control_subs[i] > 0) { if (_poll_fds[poll_id].revents & POLLIN) { @@ -317,7 +318,7 @@ int UavcanNode::run() // XXX trigger failsafe } - //can we mix? + // can we mix? if (controls_updated && (_mixers != nullptr)) { // XXX one output group has 8 outputs max, @@ -417,7 +418,8 @@ UavcanNode::subscribe() // Subscribe/unsubscribe to required actuator control groups uint32_t sub_groups = _groups_required & ~_groups_subscribed; uint32_t unsub_groups = _groups_subscribed & ~_groups_required; - _poll_fds_num = 0; + // the first fd used by CAN + _poll_fds_num = 1; for (unsigned i = 0; i < NUM_ACTUATOR_CONTROL_GROUPS; i++) { if (sub_groups & (1 << i)) { warnx("subscribe to actuator_controls_%d", i); @@ -523,8 +525,8 @@ UavcanNode::print_info() warnx("not running, start first"); } - warnx("groups: sub: %u / req: %u / fds: %u", (unsigned)_groups_subscribed, (unsigned)_groups_required, _poll_fds_num); - warnx("mixer: %s", (_mixers == nullptr) ? "FAIL" : "OK"); + warnx("actuators control groups: sub: %u / req: %u / fds: %u", (unsigned)_groups_subscribed, (unsigned)_groups_required, _poll_fds_num); + warnx("mixer: %s", (_mixers == nullptr) ? "NONE" : "OK"); } /* -- cgit v1.2.3 From 020ac409be62e6c459e7aa5cb3181941c9bbfd23 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 3 Aug 2014 13:17:18 +0200 Subject: Remove airspeed and altitude raw data from TECS log, as we have these quantities already in the system log --- src/modules/fw_pos_control_l1/mtecs/mTecs.cpp | 6 ++---- src/modules/sdlog2/sdlog2.c | 6 ++---- src/modules/sdlog2/sdlog2_messages.h | 4 +--- src/modules/uORB/topics/tecs_status.h | 12 ++++++------ 4 files changed, 11 insertions(+), 17 deletions(-) diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp index 749f57a2b..bffeefc1f 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp @@ -109,8 +109,7 @@ int mTecs::updateAltitudeSpeed(float flightPathAngle, float altitude, float alti /* Write part of the status message */ _status.altitudeSp = altitudeSp; - _status.altitude = altitude; - _status.altitudeFiltered = altitudeFiltered; + _status.altitude_filtered = altitudeFiltered; /* use flightpath angle setpoint for total energy control */ @@ -146,8 +145,7 @@ int mTecs::updateFlightPathAngleSpeed(float flightPathAngle, float flightPathAng /* Write part of the status message */ _status.airspeedSp = airspeedSp; - _status.airspeed = airspeed; - _status.airspeedFiltered = airspeedFiltered; + _status.airspeed_filtered = airspeedFiltered; /* use longitudinal acceleration setpoint for total energy control */ diff --git a/src/modules/sdlog2/sdlog2.c b/src/modules/sdlog2/sdlog2.c index 31861c3fc..6c4b49452 100644 --- a/src/modules/sdlog2/sdlog2.c +++ b/src/modules/sdlog2/sdlog2.c @@ -1597,14 +1597,12 @@ int sdlog2_thread_main(int argc, char *argv[]) if (copy_if_updated(ORB_ID(tecs_status), subs.tecs_status_sub, &buf.tecs_status)) { log_msg.msg_type = LOG_TECS_MSG; log_msg.body.log_TECS.altitudeSp = buf.tecs_status.altitudeSp; - log_msg.body.log_TECS.altitude = buf.tecs_status.altitude; - log_msg.body.log_TECS.altitudeFiltered = buf.tecs_status.altitudeFiltered; + log_msg.body.log_TECS.altitudeFiltered = buf.tecs_status.altitude_filtered; log_msg.body.log_TECS.flightPathAngleSp = buf.tecs_status.flightPathAngleSp; log_msg.body.log_TECS.flightPathAngle = buf.tecs_status.flightPathAngle; log_msg.body.log_TECS.flightPathAngleFiltered = buf.tecs_status.flightPathAngleFiltered; log_msg.body.log_TECS.airspeedSp = buf.tecs_status.airspeedSp; - log_msg.body.log_TECS.airspeed = buf.tecs_status.airspeed; - log_msg.body.log_TECS.airspeedFiltered = buf.tecs_status.airspeedFiltered; + log_msg.body.log_TECS.airspeedFiltered = buf.tecs_status.airspeed_filtered; log_msg.body.log_TECS.airspeedDerivativeSp = buf.tecs_status.airspeedDerivativeSp; log_msg.body.log_TECS.airspeedDerivative = buf.tecs_status.airspeedDerivative; log_msg.body.log_TECS.totalEnergyRateSp = buf.tecs_status.totalEnergyRateSp; diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index 853a3811f..fb7609435 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -333,13 +333,11 @@ struct log_GS1B_s { #define LOG_TECS_MSG 30 struct log_TECS_s { float altitudeSp; - float altitude; float altitudeFiltered; float flightPathAngleSp; float flightPathAngle; float flightPathAngleFiltered; float airspeedSp; - float airspeed; float airspeedFiltered; float airspeedDerivativeSp; float airspeedDerivative; @@ -455,7 +453,7 @@ static const struct log_format_s log_formats[] = { LOG_FORMAT(GS0B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"), LOG_FORMAT(GS1A, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"), LOG_FORMAT(GS1B, "BBBBBBBBBBBBBBBB", "s0,s1,s2,s3,s4,s5,s6,s7,s8,s9,s10,s11,s12,s13,s14,s15"), - LOG_FORMAT(TECS, "fffffffffffffffB", "ASP,A,AF,FSP,F,FF,AsSP,As,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"), + LOG_FORMAT(TECS, "fffffffffffffB", "ASP,AF,FSP,F,FF,AsSP,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"), LOG_FORMAT(WIND, "ffff", "X,Y,CovX,CovY"), /* system-level messages, ID >= 0x80 */ diff --git a/src/modules/uORB/topics/tecs_status.h b/src/modules/uORB/topics/tecs_status.h index 33055018c..ddca19d61 100644 --- a/src/modules/uORB/topics/tecs_status.h +++ b/src/modules/uORB/topics/tecs_status.h @@ -51,11 +51,13 @@ */ typedef enum { - TECS_MODE_NORMAL, + TECS_MODE_NORMAL = 0, TECS_MODE_UNDERSPEED, TECS_MODE_TAKEOFF, TECS_MODE_LAND, - TECS_MODE_LAND_THROTTLELIM + TECS_MODE_LAND_THROTTLELIM, + TECS_MODE_BAD_DESCENT, + TECS_MODE_CLIMBOUT } tecs_mode; /** @@ -65,14 +67,12 @@ struct tecs_status_s { uint64_t timestamp; /**< timestamp, in microseconds since system start */ float altitudeSp; - float altitude; - float altitudeFiltered; + float altitude_filtered; float flightPathAngleSp; float flightPathAngle; float flightPathAngleFiltered; float airspeedSp; - float airspeed; - float airspeedFiltered; + float airspeed_filtered; float airspeedDerivativeSp; float airspeedDerivative; -- cgit v1.2.3 From 43ef622725b1114beccb722bad0538c4c0cc3175 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 3 Aug 2014 13:18:22 +0200 Subject: Reinstate TECS logging --- src/lib/external_lgpl/tecs/tecs.cpp | 40 +++++++++++++++++++----------- src/lib/external_lgpl/tecs/tecs.h | 49 +++++++++++++++++++++++-------------- 2 files changed, 57 insertions(+), 32 deletions(-) diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp index 579fb5d42..a57a0481a 100644 --- a/src/lib/external_lgpl/tecs/tecs.cpp +++ b/src/lib/external_lgpl/tecs/tecs.cpp @@ -554,18 +554,30 @@ void TECS::update_pitch_throttle(const math::Matrix<3,3> &rotMat, float pitch, f // Calculate pitch demand _update_pitch(); -// // Write internal variables to the log_tuning structure. This -// // structure will be logged in dataflash at 10Hz - // log_tuning.hgt_dem = _hgt_dem_adj; - // log_tuning.hgt = _integ3_state; - // log_tuning.dhgt_dem = _hgt_rate_dem; - // log_tuning.dhgt = _integ2_state; - // log_tuning.spd_dem = _TAS_dem_adj; - // log_tuning.spd = _integ5_state; - // log_tuning.dspd = _vel_dot; - // log_tuning.ithr = _integ6_state; - // log_tuning.iptch = _integ7_state; - // log_tuning.thr = _throttle_dem; - // log_tuning.ptch = _pitch_dem; - // log_tuning.dspd_dem = _TAS_rate_dem; + _tecs_state.timestamp = now; + + if (_underspeed) { + _tecs_state.mode = ECL_TECS_MODE_UNDERSPEED; + } else if (_badDescent) { + _tecs_state.mode = ECL_TECS_MODE_BAD_DESCENT; + } else if (_climbOutDem) { + _tecs_state.mode = ECL_TECS_MODE_CLIMBOUT; + } else { + // If no error flag applies, conclude normal + _tecs_state.mode = ECL_TECS_MODE_NORMAL; + } + + _tecs_state.hgt_dem = _hgt_dem_adj; + _tecs_state.hgt = _integ3_state; + _tecs_state.dhgt_dem = _hgt_rate_dem; + _tecs_state.dhgt = _integ2_state; + _tecs_state.spd_dem = _TAS_dem_adj; + _tecs_state.spd = _integ5_state; + _tecs_state.dspd = _vel_dot; + _tecs_state.ithr = _integ6_state; + _tecs_state.iptch = _integ7_state; + _tecs_state.thr = _throttle_dem; + _tecs_state.ptch = _pitch_dem; + _tecs_state.dspd_dem = _TAS_rate_dem; + } diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h index 752b0ddd9..bcc2d90e5 100644 --- a/src/lib/external_lgpl/tecs/tecs.h +++ b/src/lib/external_lgpl/tecs/tecs.h @@ -28,6 +28,7 @@ class __EXPORT TECS { public: TECS() : + _tecs_state {}, _update_50hz_last_usec(0), _update_speed_last_usec(0), _update_pitch_throttle_last_usec(0), @@ -120,24 +121,33 @@ public: return _spdWeight; } - // log data on internal state of the controller. Called at 10Hz - // void log_data(DataFlash_Class &dataflash, uint8_t msgid); - - // struct PACKED log_TECS_Tuning { - // LOG_PACKET_HEADER; - // float hgt; - // float dhgt; - // float hgt_dem; - // float dhgt_dem; - // float spd_dem; - // float spd; - // float dspd; - // float ithr; - // float iptch; - // float thr; - // float ptch; - // float dspd_dem; - // } log_tuning; + enum ECL_TECS_MODE { + ECL_TECS_MODE_NORMAL = 0, + ECL_TECS_MODE_UNDERSPEED, + ECL_TECS_MODE_BAD_DESCENT, + ECL_TECS_MODE_CLIMBOUT + }; + + struct tecs_state { + uint64_t timestamp; + float hgt; + float dhgt; + float hgt_dem; + float dhgt_dem; + float spd_dem; + float spd; + float dspd; + float ithr; + float iptch; + float thr; + float ptch; + float dspd_dem; + enum ECL_TECS_MODE mode; + }; + + void get_tecs_state(struct tecs_state& state) { + state = _tecs_state; + } void set_time_const(float time_const) { _timeConst = time_const; @@ -212,6 +222,9 @@ public: } private: + + struct tecs_state _tecs_state; + // Last time update_50Hz was called uint64_t _update_50hz_last_usec; -- cgit v1.2.3 From ff760d07b4d115ce0bc58ca8e8f98a915c4bbb67 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 3 Aug 2014 13:19:10 +0200 Subject: Add TECS logging --- .../fw_pos_control_l1/fw_pos_control_l1_main.cpp | 47 ++++++++++++++++++++++ 1 file changed, 47 insertions(+) diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp index 189a19d48..350ce6dec 100644 --- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp +++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp @@ -146,6 +146,7 @@ private: int _range_finder_sub; /**< range finder subscription */ orb_advert_t _attitude_sp_pub; /**< attitude setpoint */ + orb_advert_t _tecs_status_pub; /**< TECS status publication */ orb_advert_t _nav_capabilities_pub; /**< navigation capabilities publication */ struct vehicle_attitude_s _att; /**< vehicle attitude */ @@ -414,6 +415,7 @@ FixedwingPositionControl::FixedwingPositionControl() : /* publications */ _attitude_sp_pub(-1), + _tecs_status_pub(-1), _nav_capabilities_pub(-1), /* states */ @@ -1384,6 +1386,51 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_ climbout_mode, climbout_pitch_min_rad, throttle_min, throttle_max, throttle_cruise, pitch_min_rad, pitch_max_rad); + + struct TECS::tecs_state s; + _tecs.get_tecs_state(s); + + struct tecs_status_s t; + + t.timestamp = s.timestamp; + + switch (s.mode) { + case TECS::ECL_TECS_MODE_NORMAL: + t.mode = TECS_MODE_NORMAL; + break; + case TECS::ECL_TECS_MODE_UNDERSPEED: + t.mode = TECS_MODE_UNDERSPEED; + break; + case TECS::ECL_TECS_MODE_BAD_DESCENT: + t.mode = TECS_MODE_BAD_DESCENT; + break; + case TECS::ECL_TECS_MODE_CLIMBOUT: + t.mode = TECS_MODE_CLIMBOUT; + break; + } + + t.altitudeSp = s.hgt_dem; + t.altitude_filtered = s.hgt; + t.airspeedSp = s.spd_dem; + t.airspeed_filtered = s.spd; + + t.flightPathAngleSp = s.dhgt_dem; + t.flightPathAngle = s.dhgt; + t.flightPathAngleFiltered = s.dhgt; + + t.airspeedDerivativeSp = s.dspd_dem; + t.airspeedDerivative = s.dspd; + + t.totalEnergyRateSp = s.thr; + t.totalEnergyRate = s.ithr; + t.energyDistributionRateSp = s.ptch; + t.energyDistributionRate = s.iptch; + + if (_tecs_status_pub > 0) { + orb_publish(ORB_ID(tecs_status), _tecs_status_pub, &t); + } else { + _tecs_status_pub = orb_advertise(ORB_ID(tecs_status), &t); + } } } -- cgit v1.2.3 From 6fbeaeaacecfa532c1c4437ba51312e1c46d980d Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 4 Aug 2014 09:40:38 -0700 Subject: Update arming_state_transition calls Add new fRunPreArmChecks flag --- src/modules/commander/commander.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 2b528eef6..4f976546e 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -393,7 +393,7 @@ transition_result_t arm_disarm(bool arm, const int mavlink_fd_local, const char // Transition the armed state. By passing mavlink_fd to arming_state_transition it will // output appropriate error messages if the state cannot transition. - arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd_local); + arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, true /* fRunPreArmChecks */, mavlink_fd_local); if (arming_res == TRANSITION_CHANGED && mavlink_fd) { mavlink_log_info(mavlink_fd_local, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy); @@ -1085,7 +1085,7 @@ int commander_thread_main(int argc, char *argv[]) if (status.hil_state == HIL_STATE_OFF && safety.safety_switch_available && !safety.safety_off && armed.armed) { arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); - if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd)) { + if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, true /* fRunPreArmChecks */, mavlink_fd)) { mavlink_log_info(mavlink_fd, "DISARMED by safety switch"); arming_state_changed = true; } @@ -1288,14 +1288,14 @@ int commander_thread_main(int argc, char *argv[]) status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL; if (armed.armed) { - arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, mavlink_fd); + arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, true /* fRunPreArmChecks */, mavlink_fd); if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; } } else { - arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, mavlink_fd); + arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, true /* fRunPreArmChecks */, mavlink_fd); if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; @@ -1309,7 +1309,7 @@ int commander_thread_main(int argc, char *argv[]) /* If in INIT state, try to proceed to STANDBY state */ if (status.arming_state == ARMING_STATE_INIT && low_prio_task == LOW_PRIO_TASK_NONE) { /* TODO: check for sensors */ - arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd); + arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, true /* fRunPreArmChecks */, mavlink_fd); if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; @@ -1368,7 +1368,7 @@ int commander_thread_main(int argc, char *argv[]) if (stick_off_counter > STICK_ON_OFF_COUNTER_LIMIT) { /* disarm to STANDBY if ARMED or to STANDBY_ERROR if ARMED_ERROR */ arming_state_t new_arming_state = (status.arming_state == ARMING_STATE_ARMED ? ARMING_STATE_STANDBY : ARMING_STATE_STANDBY_ERROR); - arming_ret = arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd); + arming_ret = arming_state_transition(&status, &safety, new_arming_state, &armed, true /* fRunPreArmChecks */, mavlink_fd); if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; } @@ -1394,7 +1394,7 @@ int commander_thread_main(int argc, char *argv[]) if (status.main_state != MAIN_STATE_MANUAL) { print_reject_arm("NOT ARMING: Switch to MANUAL mode first."); } else { - arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, mavlink_fd); + arming_ret = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, true /* fRunPreArmChecks */, mavlink_fd); if (arming_ret == TRANSITION_CHANGED) { arming_state_changed = true; } @@ -2156,7 +2156,7 @@ void *commander_low_prio_loop(void *arg) int calib_ret = ERROR; /* try to go to INIT/PREFLIGHT arming state */ - if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed, mavlink_fd)) { + if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed, true /* fRunPreArmChecks */, mavlink_fd)) { answer_command(cmd, VEHICLE_CMD_RESULT_DENIED); break; } @@ -2219,7 +2219,7 @@ void *commander_low_prio_loop(void *arg) tune_negative(true); } - arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd); + arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, true /* fRunPreArmChecks */, mavlink_fd); break; } -- cgit v1.2.3 From 014fd5f47baad2f49292216eba851100aa543fef Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 4 Aug 2014 09:41:29 -0700 Subject: Add fRunPreArmChecks flag This is to allow unit tests to be written which do not perform pre-arm checks --- src/modules/commander/state_machine_helper.cpp | 13 +++++++------ src/modules/commander/state_machine_helper.h | 2 +- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/src/modules/commander/state_machine_helper.cpp b/src/modules/commander/state_machine_helper.cpp index 3c3d2f233..f8589d24b 100644 --- a/src/modules/commander/state_machine_helper.cpp +++ b/src/modules/commander/state_machine_helper.cpp @@ -99,11 +99,12 @@ static const char * const state_names[ARMING_STATE_MAX] = { }; transition_result_t -arming_state_transition(struct vehicle_status_s *status, /// current vehicle status - const struct safety_s *safety, /// current safety settings - arming_state_t new_arming_state, /// arming state requested - struct actuator_armed_s *armed, /// current armed status - const int mavlink_fd) /// mavlink fd for error reporting, 0 for none +arming_state_transition(struct vehicle_status_s *status, ///< current vehicle status + const struct safety_s *safety, ///< current safety settings + arming_state_t new_arming_state, ///< arming state requested + struct actuator_armed_s *armed, ///< current armed status + bool fRunPreArmChecks, ///< true: run the pre-arm checks, false: no pre-arm checks, for unit testing + const int mavlink_fd) ///< mavlink fd for error reporting, 0 for none { // Double check that our static arrays are still valid ASSERT(ARMING_STATE_INIT == 0); @@ -125,7 +126,7 @@ arming_state_transition(struct vehicle_status_s *status, /// current int prearm_ret = OK; /* only perform the check if we have to */ - if (new_arming_state == ARMING_STATE_ARMED) { + if (fRunPreArmChecks && new_arming_state == ARMING_STATE_ARMED) { prearm_ret = prearm_check(status, mavlink_fd); } diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h index bb1b87e71..69ce8bbce 100644 --- a/src/modules/commander/state_machine_helper.h +++ b/src/modules/commander/state_machine_helper.h @@ -57,7 +57,7 @@ typedef enum { bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed); transition_result_t arming_state_transition(struct vehicle_status_s *current_state, const struct safety_s *safety, - arming_state_t new_arming_state, struct actuator_armed_s *armed, const int mavlink_fd); + arming_state_t new_arming_state, struct actuator_armed_s *armed, bool fRunPreArmChecks, const int mavlink_fd); transition_result_t main_state_transition(struct vehicle_status_s *current_state, main_state_t new_main_state); -- cgit v1.2.3 From cfe5c45e04f65f24110f222c3de02147146081e1 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Mon, 4 Aug 2014 09:42:16 -0700 Subject: Fix broken arming unit test Also, update arming_state_transition calls to add new fRunPreArmChecks flag. --- .../commander/commander_tests/state_machine_helper_test.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/commander/commander_tests/state_machine_helper_test.cpp b/src/modules/commander/commander_tests/state_machine_helper_test.cpp index 2e18c4284..08dda2fab 100644 --- a/src/modules/commander/commander_tests/state_machine_helper_test.cpp +++ b/src/modules/commander/commander_tests/state_machine_helper_test.cpp @@ -286,7 +286,7 @@ bool StateMachineHelperTest::armingStateTransitionTest(void) armed.ready_to_arm = test->current_state.ready_to_arm; // Attempt transition - transition_result_t result = arming_state_transition(&status, &safety, test->requested_state, &armed, 0 /* no mavlink_fd */); + transition_result_t result = arming_state_transition(&status, &safety, test->requested_state, &armed, false /* no pre-arm checks */, 0 /* no mavlink_fd */); // Validate result of transition ut_assert(test->assertMsg, test->expected_transition_result == result); @@ -335,12 +335,12 @@ bool StateMachineHelperTest::mainStateTransitionTest(void) MTT_ALL_NOT_VALID, MAIN_STATE_ACRO, MAIN_STATE_MANUAL, TRANSITION_CHANGED }, - { "transition: MANUAL to AUTO_MISSION - global position valid", - MTT_GLOBAL_POS_VALID, + { "transition: MANUAL to AUTO_MISSION - global position valid, home position valid", + MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID, MAIN_STATE_MANUAL, MAIN_STATE_AUTO_MISSION, TRANSITION_CHANGED }, - { "transition: AUTO_MISSION to MANUAL - global position valid", - MTT_GLOBAL_POS_VALID, + { "transition: AUTO_MISSION to MANUAL - global position valid, home position valid", + MTT_GLOBAL_POS_VALID | MTT_HOME_POS_VALID, MAIN_STATE_AUTO_MISSION, MAIN_STATE_MANUAL, TRANSITION_CHANGED }, { "transition: MANUAL to AUTO_LOITER - global position valid", -- cgit v1.2.3 From 33762ce861b06cfa521d75fc18df3c7237e3a423 Mon Sep 17 00:00:00 2001 From: Pavel Kirienko Date: Wed, 6 Aug 2014 12:40:07 +0400 Subject: UAVCAN ESC mixer: removed the failsafe placeholder, it's no use here --- src/modules/uavcan/uavcan_main.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/src/modules/uavcan/uavcan_main.cpp b/src/modules/uavcan/uavcan_main.cpp index 5b1539e3e..4535b6d6a 100644 --- a/src/modules/uavcan/uavcan_main.cpp +++ b/src/modules/uavcan/uavcan_main.cpp @@ -313,11 +313,6 @@ int UavcanNode::run() } } - if (!controls_updated) { - // timeout: no control data, switch to failsafe values - // XXX trigger failsafe - } - // can we mix? if (controls_updated && (_mixers != nullptr)) { -- cgit v1.2.3 From 13b9cd0cec2d10d6252d0e8015d000f4fcc1517f Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 7 Aug 2014 07:25:20 +0200 Subject: Do not fuse height after innovation consistency check fail --- src/modules/ekf_att_pos_estimator/estimator_23states.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index ffdd29a5b..c619735c6 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -1070,10 +1070,18 @@ void AttPosEKF::FuseVelposNED() // apply a 10-sigma threshold current_ekf_state.hgtHealth = sq(hgtInnov) < 100.0f*varInnovVelPos[5]; current_ekf_state.hgtTimeout = (millis() - current_ekf_state.hgtFailTime) > hgtRetryTime; - if (current_ekf_state.hgtHealth || current_ekf_state.hgtTimeout) + if (current_ekf_state.hgtHealth || current_ekf_state.hgtTimeout || staticMode) { current_ekf_state.hgtHealth = true; current_ekf_state.hgtFailTime = millis(); + + // if we just reset from a timeout, do not fuse + // the height data, but reset height and stored states + if (current_ekf_state.hgtTimeout) { + ResetHeight(); + ResetStoredStates(); + fuseHgtData = false; + } } else { -- cgit v1.2.3 From 20c3a329c72ca5950f7bb037473a812b4dd74b1b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 7 Aug 2014 07:36:59 +0200 Subject: Introduce similar checks fo all other health checks in the filter --- .../ekf_att_pos_estimator/estimator_23states.cpp | 21 +++++++++++++++++++-- 1 file changed, 19 insertions(+), 2 deletions(-) diff --git a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp index c619735c6..c7c7305b2 100644 --- a/src/modules/ekf_att_pos_estimator/estimator_23states.cpp +++ b/src/modules/ekf_att_pos_estimator/estimator_23states.cpp @@ -1032,10 +1032,16 @@ void AttPosEKF::FuseVelposNED() // apply a 5-sigma threshold current_ekf_state.velHealth = (sq(velInnov[0]) + sq(velInnov[1]) + sq(velInnov[2])) < 25.0f * (varInnovVelPos[0] + varInnovVelPos[1] + varInnovVelPos[2]); current_ekf_state.velTimeout = (millis() - current_ekf_state.velFailTime) > horizRetryTime; - if (current_ekf_state.velHealth || current_ekf_state.velTimeout) - { + if (current_ekf_state.velHealth || staticMode) { current_ekf_state.velHealth = true; current_ekf_state.velFailTime = millis(); + } else if (current_ekf_state.velTimeout || !current_ekf_state.posHealth) { + // XXX check + current_ekf_state.velHealth = true; + ResetVelocity(); + ResetStoredStates(); + // do not fuse bad data + fuseVelData = false; } else { @@ -1056,6 +1062,17 @@ void AttPosEKF::FuseVelposNED() { current_ekf_state.posHealth = true; current_ekf_state.posFailTime = millis(); + + if (current_ekf_state.posTimeout) { + ResetPosition(); + + // XXX cross-check the state reset + ResetStoredStates(); + + // do not fuse position data on this time + // step + fusePosData = false; + } } else { -- cgit v1.2.3 From faaeaeb11333598abd17db2189a2bc47216d0a98 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 8 Aug 2014 00:22:57 +0200 Subject: mc_pos_control: manual and offboard control reorganization and cleanup --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 271 +++++++++++---------- .../uORB/topics/position_setpoint_triplet.h | 8 +- 2 files changed, 140 insertions(+), 139 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index d22f43b5a..a0837a2dd 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -105,6 +105,7 @@ public: int start(); private: + const float alt_ctl_dz = 0.2f; bool _task_should_exit; /**< if true, task should exit */ int _control_task; /**< task handle for task */ @@ -184,6 +185,8 @@ private: math::Vector<3> _vel; math::Vector<3> _vel_sp; math::Vector<3> _vel_prev; /**< velocity on previous step */ + math::Vector<3> _vel_ff; + math::Vector<3> _sp_move_rate; /** * Update our local parameter cache. @@ -216,6 +219,16 @@ private: */ void reset_alt_sp(); + /** + * Set position setpoint using manual control + */ + void control_manual(float dt); + + /** + * Set position setpoint using offboard control + */ + void control_offboard(float dt); + /** * Select between barometric and global (AMSL) altitudes */ @@ -297,6 +310,8 @@ MulticopterPositionControl::MulticopterPositionControl() : _vel.zero(); _vel_sp.zero(); _vel_prev.zero(); + _vel_ff.zero(); + _sp_move_rate.zero(); _params_handles.thr_min = param_find("MPC_THR_MIN"); _params_handles.thr_max = param_find("MPC_THR_MAX"); @@ -515,6 +530,120 @@ MulticopterPositionControl::reset_alt_sp() } } +void +MulticopterPositionControl::control_manual(float dt) +{ + _sp_move_rate.zero(); + + if (_control_mode.flag_control_altitude_enabled) { + /* move altitude setpoint with throttle stick */ + _sp_move_rate(2) = -scale_control(_manual.z - 0.5f, 0.5f, alt_ctl_dz); + } + + if (_control_mode.flag_control_position_enabled) { + /* move position setpoint with roll/pitch stick */ + _sp_move_rate(0) = _manual.x; + _sp_move_rate(1) = _manual.y; + } + + /* limit setpoint move rate */ + float sp_move_norm = _sp_move_rate.length(); + + if (sp_move_norm > 1.0f) { + _sp_move_rate /= sp_move_norm; + } + + /* _sp_move_rate scaled to 0..1, scale it to max speed and rotate around yaw */ + math::Matrix<3, 3> R_yaw_sp; + R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body); + _sp_move_rate = R_yaw_sp * _sp_move_rate.emult(_params.vel_max); + + if (_control_mode.flag_control_altitude_enabled) { + /* reset alt setpoint to current altitude if needed */ + reset_alt_sp(); + } + + if (_control_mode.flag_control_position_enabled) { + /* reset position setpoint to current position if needed */ + reset_pos_sp(); + } + + /* feed forward setpoint move rate with weight vel_ff */ + _vel_ff = _sp_move_rate.emult(_params.vel_ff); + + /* move position setpoint */ + _pos_sp += _sp_move_rate * dt; + + /* check if position setpoint is too far from actual position */ + math::Vector<3> pos_sp_offs; + pos_sp_offs.zero(); + + if (_control_mode.flag_control_position_enabled) { + pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0); + pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1); + } + + if (_control_mode.flag_control_altitude_enabled) { + pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2); + } + + float pos_sp_offs_norm = pos_sp_offs.length(); + + if (pos_sp_offs_norm > 1.0f) { + pos_sp_offs /= pos_sp_offs_norm; + _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max); + } +} + +void +MulticopterPositionControl::control_offboard(float dt) +{ + bool updated; + orb_check(_pos_sp_triplet_sub, &updated); + + if (updated) { + orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet); + } + + if (_pos_sp_triplet.current.valid) { + if (_control_mode.flag_control_position_enabled && _pos_sp_triplet.current.position_valid) { + /* control position */ + _pos_sp(0) = _pos_sp_triplet.current.x; + _pos_sp(1) = _pos_sp_triplet.current.y; + _pos_sp(2) = _pos_sp_triplet.current.z; + _att_sp.yaw_body = _pos_sp_triplet.current.yaw; + + } else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) { + /* control velocity */ + /* reset position setpoint to current position if needed */ + reset_pos_sp(); + + /* set position setpoint move rate */ + _sp_move_rate(0) = _pos_sp_triplet.current.vx; + _sp_move_rate(1) = _pos_sp_triplet.current.vy; + _att_sp.yaw_body = _att_sp.yaw_body + _pos_sp_triplet.current.yawspeed * dt; + } + + if (_control_mode.flag_control_altitude_enabled) { + /* reset alt setpoint to current altitude if needed */ + reset_alt_sp(); + + /* set altitude setpoint move rate */ + _sp_move_rate(2) = _pos_sp_triplet.current.vz; + } + + /* feed forward setpoint move rate with weight vel_ff */ + _vel_ff = _sp_move_rate.emult(_params.vel_ff); + + /* move position setpoint */ + _pos_sp += _sp_move_rate * dt; + + } else { + reset_pos_sp(); + reset_alt_sp(); + } +} + void MulticopterPositionControl::task_main() { @@ -553,13 +682,6 @@ MulticopterPositionControl::task_main() hrt_abstime t_prev = 0; - const float alt_ctl_dz = 0.2f; - - math::Vector<3> sp_move_rate; - sp_move_rate.zero(); - - float yaw_sp_move_rate; - math::Vector<3> thrust_int; thrust_int.zero(); math::Matrix<3, 3> R; @@ -618,138 +740,17 @@ MulticopterPositionControl::task_main() _vel(1) = _local_pos.vy; _vel(2) = _local_pos.vz; - sp_move_rate.zero(); + _vel_ff.zero(); + _sp_move_rate.zero(); /* select control source */ if (_control_mode.flag_control_manual_enabled) { /* manual control */ - if (_control_mode.flag_control_altitude_enabled) { - /* reset alt setpoint to current altitude if needed */ - reset_alt_sp(); - - /* move altitude setpoint with throttle stick */ - sp_move_rate(2) = -scale_control(_manual.z - 0.5f, 0.5f, alt_ctl_dz); - } - - if (_control_mode.flag_control_position_enabled) { - /* reset position setpoint to current position if needed */ - reset_pos_sp(); - - /* move position setpoint with roll/pitch stick */ - sp_move_rate(0) = _manual.x; - sp_move_rate(1) = _manual.y; - } - - /* limit setpoint move rate */ - float sp_move_norm = sp_move_rate.length(); - - if (sp_move_norm > 1.0f) { - sp_move_rate /= sp_move_norm; - } - - /* scale to max speed and rotate around yaw */ - math::Matrix<3, 3> R_yaw_sp; - R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body); - sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max); - - /* move position setpoint */ - _pos_sp += sp_move_rate * dt; - - /* check if position setpoint is too far from actual position */ - math::Vector<3> pos_sp_offs; - pos_sp_offs.zero(); - - if (_control_mode.flag_control_position_enabled) { - pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0); - pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1); - } - - if (_control_mode.flag_control_altitude_enabled) { - pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2); - } - - float pos_sp_offs_norm = pos_sp_offs.length(); - - if (pos_sp_offs_norm > 1.0f) { - pos_sp_offs /= pos_sp_offs_norm; - _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max); - } + control_manual(dt); } else if (_control_mode.flag_control_offboard_enabled) { - /* Offboard control */ - bool updated; - orb_check(_pos_sp_triplet_sub, &updated); - - if (updated) { - orb_copy(ORB_ID(position_setpoint_triplet), _pos_sp_triplet_sub, &_pos_sp_triplet); - } - - if (_pos_sp_triplet.current.valid) { - - if (_control_mode.flag_control_position_enabled && _pos_sp_triplet.current.position_valid) { - - _pos_sp(0) = _pos_sp_triplet.current.x; - _pos_sp(1) = _pos_sp_triplet.current.y; - _pos_sp(2) = _pos_sp_triplet.current.z; - _att_sp.yaw_body = _pos_sp_triplet.current.yaw; - - } else if (_control_mode.flag_control_velocity_enabled && _pos_sp_triplet.current.velocity_valid) { - /* reset position setpoint to current position if needed */ - reset_pos_sp(); - /* move position setpoint with roll/pitch stick */ - sp_move_rate(0) = _pos_sp_triplet.current.vx; - sp_move_rate(1) = _pos_sp_triplet.current.vy; - yaw_sp_move_rate = _pos_sp_triplet.current.yawspeed; - _att_sp.yaw_body = _att.yaw + yaw_sp_move_rate * dt; - } - - if (_control_mode.flag_control_altitude_enabled) { - /* reset alt setpoint to current altitude if needed */ - reset_alt_sp(); - - /* move altitude setpoint with throttle stick */ - sp_move_rate(2) = -scale_control(_pos_sp_triplet.current.vz - 0.5f, 0.5f, alt_ctl_dz);; - } - - /* limit setpoint move rate */ - float sp_move_norm = sp_move_rate.length(); - - if (sp_move_norm > 1.0f) { - sp_move_rate /= sp_move_norm; - } - - /* scale to max speed and rotate around yaw */ - math::Matrix<3, 3> R_yaw_sp; - R_yaw_sp.from_euler(0.0f, 0.0f, _att_sp.yaw_body); - sp_move_rate = R_yaw_sp * sp_move_rate.emult(_params.vel_max); - - /* move position setpoint */ - _pos_sp += sp_move_rate * dt; - - /* check if position setpoint is too far from actual position */ - math::Vector<3> pos_sp_offs; - pos_sp_offs.zero(); - - if (_control_mode.flag_control_position_enabled) { - pos_sp_offs(0) = (_pos_sp(0) - _pos(0)) / _params.sp_offs_max(0); - pos_sp_offs(1) = (_pos_sp(1) - _pos(1)) / _params.sp_offs_max(1); - } - - if (_control_mode.flag_control_altitude_enabled) { - pos_sp_offs(2) = (_pos_sp(2) - _pos(2)) / _params.sp_offs_max(2); - } - - float pos_sp_offs_norm = pos_sp_offs.length(); - - if (pos_sp_offs_norm > 1.0f) { - pos_sp_offs /= pos_sp_offs_norm; - _pos_sp = _pos + pos_sp_offs.emult(_params.sp_offs_max); - } - - } else { - reset_pos_sp(); - reset_alt_sp(); - } + /* offboard control */ + control_offboard(dt); } else { /* AUTO */ @@ -823,7 +824,7 @@ MulticopterPositionControl::task_main() /* run position & altitude controllers, calculate velocity setpoint */ math::Vector<3> pos_err = _pos_sp - _pos; - _vel_sp = pos_err.emult(_params.pos_p) + sp_move_rate.emult(_params.vel_ff); + _vel_sp = pos_err.emult(_params.pos_p) + _vel_ff; if (!_control_mode.flag_control_altitude_enabled) { _reset_alt_sp = true; @@ -903,7 +904,7 @@ MulticopterPositionControl::task_main() math::Vector<3> vel_err = _vel_sp - _vel; /* derivative of velocity error, not includes setpoint acceleration */ - math::Vector<3> vel_err_d = (sp_move_rate - _vel).emult(_params.pos_p) - (_vel - _vel_prev) / dt; + math::Vector<3> vel_err_d = (_sp_move_rate - _vel).emult(_params.pos_p) - (_vel - _vel_prev) / dt; _vel_prev = _vel; /* thrust vector in NED frame */ diff --git a/src/modules/uORB/topics/position_setpoint_triplet.h b/src/modules/uORB/topics/position_setpoint_triplet.h index 4a1932180..ec2131abd 100644 --- a/src/modules/uORB/topics/position_setpoint_triplet.h +++ b/src/modules/uORB/topics/position_setpoint_triplet.h @@ -60,7 +60,7 @@ enum SETPOINT_TYPE SETPOINT_TYPE_TAKEOFF, /**< takeoff setpoint */ SETPOINT_TYPE_LAND, /**< land setpoint, altitude must be ignored, descend until landing */ SETPOINT_TYPE_IDLE, /**< do nothing, switch off motors or keep at idle speed (MC) */ - SETPOINT_TYPE_OFFBOARD, /**< setpoint set by offboard */ + SETPOINT_TYPE_OFFBOARD, /**< setpoint in NED frame (x, y, z, vx, vy, vz) set by offboard */ }; struct position_setpoint_s @@ -71,9 +71,9 @@ struct position_setpoint_s float y; /**< local position setpoint in m in NED */ float z; /**< local position setpoint in m in NED */ bool position_valid; /**< true if local position setpoint valid */ - float vx; /**< local velocity setpoint in m in NED */ - float vy; /**< local velocity setpoint in m in NED */ - float vz; /**< local velocity setpoint in m in NED */ + float vx; /**< local velocity setpoint in m/s in NED */ + float vy; /**< local velocity setpoint in m/s in NED */ + float vz; /**< local velocity setpoint in m/s in NED */ bool velocity_valid; /**< true if local velocity setpoint valid */ double lat; /**< latitude, in deg */ double lon; /**< longitude, in deg */ -- cgit v1.2.3 From 03f839a27ac61178be8ef77526faa13a46c4cd6b Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Fri, 8 Aug 2014 00:24:18 +0200 Subject: mc_pos_control: more accurate position setpoint reset, keep attitude setpoint continuous --- src/modules/mc_pos_control/mc_pos_control_main.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index a0837a2dd..0106af80a 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -514,8 +514,11 @@ MulticopterPositionControl::reset_pos_sp() { if (_reset_pos_sp) { _reset_pos_sp = false; - _pos_sp(0) = _pos(0) + _vel(0) / _params.pos_p(0) * (1.0f - _params.vel_ff(0)); - _pos_sp(1) = _pos(1) + _vel(1) / _params.pos_p(1) * (1.0f - _params.vel_ff(1)); + /* shift position setpoint to make attitude setpoint continuous */ + _pos_sp(0) = _pos(0) + (_vel(0) - _att_sp.R_body[0][2] * _att_sp.thrust / _params.vel_p(0) + - _params.vel_ff(0) * _sp_move_rate(0)) / _params.pos_p(0); + _pos_sp(1) = _pos(1) + (_vel(1) - _att_sp.R_body[1][2] * _att_sp.thrust / _params.vel_p(1) + - _params.vel_ff(1) * _sp_move_rate(1)) / _params.pos_p(1); mavlink_log_info(_mavlink_fd, "[mpc] reset pos sp: %.2f, %.2f", (double)_pos_sp(0), (double)_pos_sp(1)); } } @@ -525,7 +528,7 @@ MulticopterPositionControl::reset_alt_sp() { if (_reset_alt_sp) { _reset_alt_sp = false; - _pos_sp(2) = _pos(2) + _vel(2) / _params.pos_p(2) * (1.0f - _params.vel_ff(2)); + _pos_sp(2) = _pos(2) + (_vel(2) - _params.vel_ff(2) * _sp_move_rate(2)) / _params.pos_p(2); mavlink_log_info(_mavlink_fd, "[mpc] reset alt sp: %.2f", -(double)_pos_sp(2)); } } -- cgit v1.2.3 From 5246d6b49211b7ba73a32c7b73967cabe5fd512a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 9 Aug 2014 19:31:34 +0200 Subject: Updated mavlink version --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 04b1ad5b2..96425caae 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 04b1ad5b284d5e916858ca9f928e93d97bbf6ad9 +Subproject commit 96425caae3de0e8cda81405c1a0e9d2fb14369a2 -- cgit v1.2.3 From 312f9e0ccce9e3f530f6fc222e371a48c3b1af0d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 9 Aug 2014 19:43:57 +0200 Subject: mixers: adapted FX79 mixer to have more pitch influence --- ROMFS/px4fmu_common/mixers/FMU_FX79.mix | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix index 0a1dca98d..112d9b891 100755 --- a/ROMFS/px4fmu_common/mixers/FMU_FX79.mix +++ b/ROMFS/px4fmu_common/mixers/FMU_FX79.mix @@ -27,12 +27,12 @@ for the elevons. M: 2 O: 10000 10000 0 -10000 10000 -S: 0 0 5000 8000 0 -10000 10000 +S: 0 0 7500 7500 0 -10000 10000 S: 0 1 8000 8000 0 -10000 10000 M: 2 O: 10000 10000 0 -10000 10000 -S: 0 0 8000 5000 0 -10000 10000 +S: 0 0 7500 7500 0 -10000 10000 S: 0 1 -8000 -8000 0 -10000 10000 Output 2 -- cgit v1.2.3 From 3fdf63d2b3cf25904371cf700e08ce4e8d214824 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sun, 30 Mar 2014 15:00:37 +0200 Subject: Startup script: added viper script Conflicts: mavlink/include/mavlink/v1.0 --- ROMFS/px4fmu_common/init.d/3035_viper | 10 ++++++++++ ROMFS/px4fmu_common/init.d/rc.autostart | 5 +++++ 2 files changed, 15 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d/3035_viper diff --git a/ROMFS/px4fmu_common/init.d/3035_viper b/ROMFS/px4fmu_common/init.d/3035_viper new file mode 100644 index 000000000..9c8f8a585 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/3035_viper @@ -0,0 +1,10 @@ +#!nsh +# +# Viper +# +# Simon Wilks +# + +sh /etc/init.d/rc.fw_defaults + +set MIXER FMU_FX79 \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rc.autostart b/ROMFS/px4fmu_common/init.d/rc.autostart index 17541e680..9de7d9ecd 100644 --- a/ROMFS/px4fmu_common/init.d/rc.autostart +++ b/ROMFS/px4fmu_common/init.d/rc.autostart @@ -103,6 +103,11 @@ then sh /etc/init.d/3034_fx79 fi +if param compare SYS_AUTOSTART 3035 35 +then + sh /etc/init.d/3035_viper +fi + if param compare SYS_AUTOSTART 3100 then sh /etc/init.d/3100_tbs_caipirinha -- cgit v1.2.3 From e6210058a3527bc87a74781159631a1f59ad053d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Sat, 9 Aug 2014 19:52:30 +0200 Subject: mixers: added Viper mixer --- ROMFS/px4fmu_common/init.d/3035_viper | 2 +- ROMFS/px4fmu_common/mixers/Viper.mix | 72 +++++++++++++++++++++++++++++++++++ 2 files changed, 73 insertions(+), 1 deletion(-) create mode 100755 ROMFS/px4fmu_common/mixers/Viper.mix diff --git a/ROMFS/px4fmu_common/init.d/3035_viper b/ROMFS/px4fmu_common/init.d/3035_viper index 9c8f8a585..a4c1e832d 100644 --- a/ROMFS/px4fmu_common/init.d/3035_viper +++ b/ROMFS/px4fmu_common/init.d/3035_viper @@ -7,4 +7,4 @@ sh /etc/init.d/rc.fw_defaults -set MIXER FMU_FX79 \ No newline at end of file +set MIXER Viper diff --git a/ROMFS/px4fmu_common/mixers/Viper.mix b/ROMFS/px4fmu_common/mixers/Viper.mix new file mode 100755 index 000000000..79c4447be --- /dev/null +++ b/ROMFS/px4fmu_common/mixers/Viper.mix @@ -0,0 +1,72 @@ +Viper Delta-wing mixer +================================= + +Designed for Viper. + +TODO (sjwilks): Add mixers for flaps. + +This file defines mixers suitable for controlling a delta wing aircraft using +PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU +servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is +assumed to be unused. + +Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0 +(roll), 1 (pitch) and 3 (thrust). + +See the README for more information on the scaler format. + +Elevon mixers +------------- +Three scalers total (output, roll, pitch). + +On the assumption that the two elevon servos are physically reversed, the pitch +input is inverted between the two servos. + +The scaling factor for roll inputs is adjusted to implement differential travel +for the elevons. + +M: 2 +O: 10000 10000 0 -10000 10000 +S: 0 0 7500 7500 0 -10000 10000 +S: 0 1 8000 8000 0 -10000 10000 + +M: 2 +O: 10000 10000 0 -10000 10000 +S: 0 0 7500 7500 0 -10000 10000 +S: 0 1 -8000 -8000 0 -10000 10000 + +Output 2 +-------- +This mixer is empty. + +Z: + +Motor speed mixer +----------------- +Two scalers total (output, thrust). + +This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1) +range. Inputs below zero are treated as zero. + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 3 0 20000 -10000 -10000 10000 + +Gimbal / flaps / payload mixer for last four channels +----------------------------------------------------- + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 4 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 5 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 6 10000 10000 0 -10000 10000 + +M: 1 +O: 10000 10000 0 -10000 10000 +S: 0 7 10000 10000 0 -10000 10000 -- cgit v1.2.3 From 4b065a7e1d2a523ba40abbf63452bf89d1004cd8 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 10 Aug 2014 00:52:03 +0200 Subject: Updated MAVLink version --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 96425caae..8cc21472c 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 96425caae3de0e8cda81405c1a0e9d2fb14369a2 +Subproject commit 8cc21472cce09709d4c651e2855d891843a17e41 -- cgit v1.2.3 From 5225d87854bdea1b5e4367e3db6b41ece9e46e13 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 10 Aug 2014 01:24:04 +0200 Subject: Updated MAVLink to latest revision --- src/modules/mavlink/mavlink_messages.cpp | 151 ++++++++++--------------------- src/modules/mavlink/mavlink_receiver.cpp | 34 ------- 2 files changed, 49 insertions(+), 136 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 683f0f1e8..7f67475f2 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1385,43 +1385,43 @@ protected: }; -class MavlinkStreamGlobalPositionSetpointInt : public MavlinkStream +class MavlinkStreamPositionTargetGlobalInt : public MavlinkStream { public: const char *get_name() const { - return MavlinkStreamGlobalPositionSetpointInt::get_name_static(); + return MavlinkStreamPositionTargetGlobalInt::get_name_static(); } static const char *get_name_static() { - return "GLOBAL_POSITION_SETPOINT_INT"; + return "POSITION_TARGET_GLOBAL_INT"; } uint8_t get_id() { - return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT; + return MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT; } static MavlinkStream *new_instance(Mavlink *mavlink) { - return new MavlinkStreamGlobalPositionSetpointInt(mavlink); + return new MavlinkStreamPositionTargetGlobalInt(mavlink); } unsigned get_size() { - return MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + return MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; } private: MavlinkOrbSubscription *_pos_sp_triplet_sub; /* do not allow top copying this class */ - MavlinkStreamGlobalPositionSetpointInt(MavlinkStreamGlobalPositionSetpointInt &); - MavlinkStreamGlobalPositionSetpointInt& operator = (const MavlinkStreamGlobalPositionSetpointInt &); + MavlinkStreamPositionTargetGlobalInt(MavlinkStreamPositionTargetGlobalInt &); + MavlinkStreamPositionTargetGlobalInt& operator = (const MavlinkStreamPositionTargetGlobalInt &); protected: - explicit MavlinkStreamGlobalPositionSetpointInt(Mavlink *mavlink) : MavlinkStream(mavlink), + explicit MavlinkStreamPositionTargetGlobalInt(Mavlink *mavlink) : MavlinkStream(mavlink), _pos_sp_triplet_sub(_mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet))) {} @@ -1430,15 +1430,14 @@ protected: struct position_setpoint_triplet_s pos_sp_triplet; if (_pos_sp_triplet_sub->update(&pos_sp_triplet)) { - mavlink_global_position_setpoint_int_t msg; + mavlink_position_target_global_int_t msg; msg.coordinate_frame = MAV_FRAME_GLOBAL; - msg.latitude = pos_sp_triplet.current.lat * 1e7; - msg.longitude = pos_sp_triplet.current.lon * 1e7; - msg.altitude = pos_sp_triplet.current.alt * 1000; - msg.yaw = pos_sp_triplet.current.yaw * M_RAD_TO_DEG_F * 100.0f; + msg.lat_int = pos_sp_triplet.current.lat * 1e7; + msg.lon_int = pos_sp_triplet.current.lon * 1e7; + msg.alt = pos_sp_triplet.current.alt; - _mavlink->send_message(MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, &msg); + _mavlink->send_message(MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, &msg); } } }; @@ -1454,12 +1453,12 @@ public: static const char *get_name_static() { - return "LOCAL_POSITION_SETPOINT"; + return "POSITION_TARGET_LOCAL_NED"; } uint8_t get_id() { - return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT; + return MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED; } static MavlinkStream *new_instance(Mavlink *mavlink) @@ -1469,7 +1468,7 @@ public: unsigned get_size() { - return MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + return MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; } private: @@ -1491,137 +1490,86 @@ protected: struct vehicle_local_position_setpoint_s pos_sp; if (_pos_sp_sub->update(&_pos_sp_time, &pos_sp)) { - mavlink_local_position_setpoint_t msg; + mavlink_position_target_local_ned_t msg; msg.coordinate_frame = MAV_FRAME_LOCAL_NED; msg.x = pos_sp.x; msg.y = pos_sp.y; msg.z = pos_sp.z; - msg.yaw = pos_sp.yaw; - _mavlink->send_message(MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, &msg); + _mavlink->send_message(MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, &msg); } } }; -class MavlinkStreamRollPitchYawThrustSetpoint : public MavlinkStream +class MavlinkStreamAttitudeTarget : public MavlinkStream { public: const char *get_name() const { - return MavlinkStreamRollPitchYawThrustSetpoint::get_name_static(); + return MavlinkStreamAttitudeTarget::get_name_static(); } static const char *get_name_static() { - return "ROLL_PITCH_YAW_THRUST_SETPOINT"; + return "ATTITUDE_TARGET"; } uint8_t get_id() { - return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT; + return MAVLINK_MSG_ID_ATTITUDE_TARGET; } static MavlinkStream *new_instance(Mavlink *mavlink) { - return new MavlinkStreamRollPitchYawThrustSetpoint(mavlink); + return new MavlinkStreamAttitudeTarget(mavlink); } unsigned get_size() { - return MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; + return MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; } private: - MavlinkOrbSubscription *att_sp_sub; - uint64_t att_sp_time; + MavlinkOrbSubscription *_att_sp_sub; + MavlinkOrbSubscription *_att_rates_sp_sub; + uint64_t _att_sp_time; + uint64_t _att_rates_sp_time; /* do not allow top copying this class */ - MavlinkStreamRollPitchYawThrustSetpoint(MavlinkStreamRollPitchYawThrustSetpoint &); - MavlinkStreamRollPitchYawThrustSetpoint& operator = (const MavlinkStreamRollPitchYawThrustSetpoint &); + MavlinkStreamAttitudeTarget(MavlinkStreamAttitudeTarget &); + MavlinkStreamAttitudeTarget& operator = (const MavlinkStreamAttitudeTarget &); protected: - explicit MavlinkStreamRollPitchYawThrustSetpoint(Mavlink *mavlink) : MavlinkStream(mavlink), - att_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint))), - att_sp_time(0) + explicit MavlinkStreamAttitudeTarget(Mavlink *mavlink) : MavlinkStream(mavlink), + _att_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint))), + _att_rates_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint))), + _att_sp_time(0), + _att_rates_sp_time(0) {} void send(const hrt_abstime t) { struct vehicle_attitude_setpoint_s att_sp; - if (att_sp_sub->update(&att_sp_time, &att_sp)) { - mavlink_roll_pitch_yaw_thrust_setpoint_t msg; - - msg.time_boot_ms = att_sp.timestamp / 1000; - msg.roll = att_sp.roll_body; - msg.pitch = att_sp.pitch_body; - msg.yaw = att_sp.yaw_body; - msg.thrust = att_sp.thrust; - - _mavlink->send_message(MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, &msg); - } - } -}; - + if (_att_sp_sub->update(&_att_sp_time, &att_sp)) { -class MavlinkStreamRollPitchYawRatesThrustSetpoint : public MavlinkStream -{ -public: - const char *get_name() const - { - return MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static(); - } - - static const char *get_name_static() - { - return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT"; - } + struct vehicle_rates_setpoint_s att_rates_sp; + (void)_att_rates_sp_sub->update(&_att_rates_sp_time, &att_rates_sp); - uint8_t get_id() - { - return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT; - } + mavlink_attitude_target_t msg; - static MavlinkStream *new_instance(Mavlink *mavlink) - { - return new MavlinkStreamRollPitchYawRatesThrustSetpoint(mavlink); - } - - unsigned get_size() - { - return MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES; - } - -private: - MavlinkOrbSubscription *_att_rates_sp_sub; - uint64_t _att_rates_sp_time; - - /* do not allow top copying this class */ - MavlinkStreamRollPitchYawRatesThrustSetpoint(MavlinkStreamRollPitchYawRatesThrustSetpoint &); - MavlinkStreamRollPitchYawRatesThrustSetpoint& operator = (const MavlinkStreamRollPitchYawRatesThrustSetpoint &); - -protected: - explicit MavlinkStreamRollPitchYawRatesThrustSetpoint(Mavlink *mavlink) : MavlinkStream(mavlink), - _att_rates_sp_sub(_mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint))), - _att_rates_sp_time(0) - {} - - void send(const hrt_abstime t) - { - struct vehicle_rates_setpoint_s att_rates_sp; + msg.time_boot_ms = att_sp.timestamp / 1000; + mavlink_euler_to_quaternion(att_sp.roll_body, att_sp.pitch_body, att_sp.yaw_body, msg.q); - if (_att_rates_sp_sub->update(&_att_rates_sp_time, &att_rates_sp)) { - mavlink_roll_pitch_yaw_rates_thrust_setpoint_t msg; + msg.body_roll_rate = att_rates_sp.roll; + msg.body_pitch_rate = att_rates_sp.pitch; + msg.body_yaw_rate = att_rates_sp.yaw; - msg.time_boot_ms = att_rates_sp.timestamp / 1000; - msg.roll_rate = att_rates_sp.roll; - msg.pitch_rate = att_rates_sp.pitch; - msg.yaw_rate = att_rates_sp.yaw; - msg.thrust = att_rates_sp.thrust; + msg.thrust = att_sp.thrust; - _mavlink->send_message(MAVLINK_MSG_ID_ROLL_PITCH_YAW_RATES_THRUST_SETPOINT, &msg); + _mavlink->send_message(MAVLINK_MSG_ID_ATTITUDE_TARGET, &msg); } } }; @@ -2149,10 +2097,9 @@ StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamServoOutputRaw<2>::new_instance, &MavlinkStreamServoOutputRaw<2>::get_name_static), new StreamListItem(&MavlinkStreamServoOutputRaw<3>::new_instance, &MavlinkStreamServoOutputRaw<3>::get_name_static), new StreamListItem(&MavlinkStreamHILControls::new_instance, &MavlinkStreamHILControls::get_name_static), - new StreamListItem(&MavlinkStreamGlobalPositionSetpointInt::new_instance, &MavlinkStreamGlobalPositionSetpointInt::get_name_static), + new StreamListItem(&MavlinkStreamPositionTargetGlobalInt::new_instance, &MavlinkStreamPositionTargetGlobalInt::get_name_static), new StreamListItem(&MavlinkStreamLocalPositionSetpoint::new_instance, &MavlinkStreamLocalPositionSetpoint::get_name_static), - new StreamListItem(&MavlinkStreamRollPitchYawThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawThrustSetpoint::get_name_static), - new StreamListItem(&MavlinkStreamRollPitchYawRatesThrustSetpoint::new_instance, &MavlinkStreamRollPitchYawRatesThrustSetpoint::get_name_static), + new StreamListItem(&MavlinkStreamAttitudeTarget::new_instance, &MavlinkStreamAttitudeTarget::get_name_static), new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamRCChannelsRaw::get_name_static), new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static), new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static), diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 69e3ef31d..63bac45c0 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -148,10 +148,6 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_vicon_position_estimate(msg); break; - case MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST: - handle_message_quad_swarm_roll_pitch_yaw_thrust(msg); - break; - case MAVLINK_MSG_ID_RADIO_STATUS: handle_message_radio_status(msg); break; @@ -362,36 +358,6 @@ MavlinkReceiver::handle_message_vicon_position_estimate(mavlink_message_t *msg) } } -void -MavlinkReceiver::handle_message_quad_swarm_roll_pitch_yaw_thrust(mavlink_message_t *msg) -{ - mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t swarm_offboard_control; - mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(msg, &swarm_offboard_control); - - /* Only accept system IDs from 1 to 4 */ - if (mavlink_system.sysid >= 1 && mavlink_system.sysid <= 4) { - struct offboard_control_setpoint_s offboard_control_sp; - memset(&offboard_control_sp, 0, sizeof(offboard_control_sp)); - - /* Convert values * 1000 back */ - offboard_control_sp.p1 = (float)swarm_offboard_control.roll[mavlink_system.sysid - 1] / 1000.0f; - offboard_control_sp.p2 = (float)swarm_offboard_control.pitch[mavlink_system.sysid - 1] / 1000.0f; - offboard_control_sp.p3 = (float)swarm_offboard_control.yaw[mavlink_system.sysid - 1] / 1000.0f; - offboard_control_sp.p4 = (float)swarm_offboard_control.thrust[mavlink_system.sysid - 1] / 1000.0f; - - offboard_control_sp.mode = (enum OFFBOARD_CONTROL_MODE)swarm_offboard_control.mode; - - offboard_control_sp.timestamp = hrt_absolute_time(); - - if (_offboard_control_sp_pub < 0) { - _offboard_control_sp_pub = orb_advertise(ORB_ID(offboard_control_setpoint), &offboard_control_sp); - - } else { - orb_publish(ORB_ID(offboard_control_setpoint), _offboard_control_sp_pub, &offboard_control_sp); - } - } -} - void MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) { -- cgit v1.2.3 From 9ecec7fada7da3778c6214defcef68ea05352027 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 10 Aug 2014 01:30:25 +0200 Subject: Add default initializers and timestamp in local position --- src/modules/mavlink/mavlink_messages.cpp | 7 ++++--- src/modules/mc_pos_control/mc_pos_control_main.cpp | 1 + src/modules/uORB/topics/vehicle_local_position_setpoint.h | 3 ++- 3 files changed, 7 insertions(+), 4 deletions(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 7f67475f2..c10be77b5 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1430,7 +1430,7 @@ protected: struct position_setpoint_triplet_s pos_sp_triplet; if (_pos_sp_triplet_sub->update(&pos_sp_triplet)) { - mavlink_position_target_global_int_t msg; + mavlink_position_target_global_int_t msg{}; msg.coordinate_frame = MAV_FRAME_GLOBAL; msg.lat_int = pos_sp_triplet.current.lat * 1e7; @@ -1490,8 +1490,9 @@ protected: struct vehicle_local_position_setpoint_s pos_sp; if (_pos_sp_sub->update(&_pos_sp_time, &pos_sp)) { - mavlink_position_target_local_ned_t msg; + mavlink_position_target_local_ned_t msg{}; + msg.time_boot_ms = pos_sp.timestamp / 1000; msg.coordinate_frame = MAV_FRAME_LOCAL_NED; msg.x = pos_sp.x; msg.y = pos_sp.y; @@ -1558,7 +1559,7 @@ protected: struct vehicle_rates_setpoint_s att_rates_sp; (void)_att_rates_sp_sub->update(&_att_rates_sp_time, &att_rates_sp); - mavlink_attitude_target_t msg; + mavlink_attitude_target_t msg{}; msg.time_boot_ms = att_sp.timestamp / 1000; mavlink_euler_to_quaternion(att_sp.roll_body, att_sp.pitch_body, att_sp.yaw_body, msg.q); diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index 0106af80a..ecc40428d 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -788,6 +788,7 @@ MulticopterPositionControl::task_main() } /* fill local position setpoint */ + _local_pos_sp.timestamp = hrt_absolute_time(); _local_pos_sp.x = _pos_sp(0); _local_pos_sp.y = _pos_sp(1); _local_pos_sp.z = _pos_sp(2); diff --git a/src/modules/uORB/topics/vehicle_local_position_setpoint.h b/src/modules/uORB/topics/vehicle_local_position_setpoint.h index 8988a0330..6766bb58a 100644 --- a/src/modules/uORB/topics/vehicle_local_position_setpoint.h +++ b/src/modules/uORB/topics/vehicle_local_position_setpoint.h @@ -50,11 +50,12 @@ */ struct vehicle_local_position_setpoint_s { + uint64_t timestamp; /**< timestamp of the setpoint */ float x; /**< in meters NED */ float y; /**< in meters NED */ float z; /**< in meters NED */ float yaw; /**< in radians NED -PI..+PI */ -}; /**< Local position in NED frame to go to */ +}; /**< Local position in NED frame */ /** * @} -- cgit v1.2.3 From 1d3edfa62976bdf73eeef67309c67b154be07810 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 10 Aug 2014 12:02:10 -0700 Subject: More FTP support Added: - sequence numbers - directory list returns file sizes - open command returns file size in data --- src/modules/mavlink/mavlink_ftp.cpp | 48 +++++++++++++++++++++++++++++++------ src/modules/mavlink/mavlink_ftp.h | 2 +- 2 files changed, 42 insertions(+), 8 deletions(-) diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index 6a2c900af..17d1babff 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include "mavlink_ftp.h" @@ -190,6 +191,8 @@ void MavlinkFTP::_reply(Request *req) { auto hdr = req->header(); + + hdr->magic = kProtocolMagic; // message is assumed to be already constructed in the request buffer, so generate the CRC hdr->crc32 = 0; @@ -242,15 +245,18 @@ MavlinkFTP::_workList(Request *req) break; } - // name too big to fit? - if ((strlen(entry.d_name) + offset + 2) > kMaxDataLength) { - break; - } + uint32_t fileSize = 0; + char buf[256]; // store the type marker switch (entry.d_type) { case DTYPE_FILE: hdr->data[offset++] = kDirentFile; + snprintf(buf, sizeof(buf), "%s/%s", dirPath, entry.d_name); + struct stat st; + if (stat(buf, &st) == 0) { + fileSize = st.st_size; + } break; case DTYPE_DIRECTORY: hdr->data[offset++] = kDirentDir; @@ -259,11 +265,24 @@ MavlinkFTP::_workList(Request *req) hdr->data[offset++] = kDirentUnknown; break; } + + if (entry.d_type == DTYPE_FILE) { + snprintf(buf, sizeof(buf), "%s\t%d", entry.d_name, fileSize); + } else { + strncpy(buf, entry.d_name, sizeof(buf)); + buf[sizeof(buf)-1] = 0; + } + size_t nameLen = strlen(buf); + // name too big to fit? + if ((nameLen + offset + 2) > kMaxDataLength) { + break; + } + // copy the name, which we know will fit - strcpy((char *)&hdr->data[offset], entry.d_name); + strcpy((char *)&hdr->data[offset], buf); //printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]); - offset += strlen(entry.d_name) + 1; + offset += nameLen + 1; } closedir(dp); @@ -282,6 +301,16 @@ MavlinkFTP::_workOpen(Request *req, bool create) return kErrNoSession; } + + uint32_t fileSize = 0; + if (!create) { + struct stat st; + if (stat(req->dataAsCString(), &st) != 0) { + return kErrNotFile; + } + fileSize = st.st_size; + } + int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY; int fd = ::open(req->dataAsCString(), oflag); @@ -291,7 +320,12 @@ MavlinkFTP::_workOpen(Request *req, bool create) _session_fds[session_index] = fd; hdr->session = session_index; - hdr->size = 0; + if (create) { + hdr->size = 0; + } else { + hdr->size = sizeof(uint32_t); + *((uint32_t*)hdr->data) = fileSize; + } return kErrNone; } diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h index 1bd1158fb..800c98b69 100644 --- a/src/modules/mavlink/mavlink_ftp.h +++ b/src/modules/mavlink/mavlink_ftp.h @@ -146,7 +146,7 @@ private: mavlink_message_t msg; msg.checksum = 0; unsigned len = mavlink_msg_encapsulated_data_pack_chan(_mavlink->get_system_id(), _mavlink->get_component_id(), - _mavlink->get_channel(), &msg, sequence(), rawData()); + _mavlink->get_channel(), &msg, sequence()+1, rawData()); _mavlink->lockMessageBufferMutex(); bool success = _mavlink->message_buffer_write(&msg, len); -- cgit v1.2.3 From 0633d7f601b38a60c2b0ed1ca98d57bd3f80e482 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sun, 10 Aug 2014 22:05:21 +0200 Subject: Updated mavlink version --- mavlink/include/mavlink/v1.0 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavlink/include/mavlink/v1.0 b/mavlink/include/mavlink/v1.0 index 8cc21472c..4cd384001 160000 --- a/mavlink/include/mavlink/v1.0 +++ b/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 8cc21472cce09709d4c651e2855d891843a17e41 +Subproject commit 4cd384001b5373e1ecaa6c4cd66994855cec4742 -- cgit v1.2.3