From bd9d58f565383598db785908a7cc08f87f6a07f1 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Mon, 12 May 2014 23:06:45 +0200 Subject: attitude_estimator_ekf: auto detect mag declination using GPS coordinates --- .../attitude_estimator_ekf_main.cpp | 26 +++++++++++++++++----- 1 file changed, 21 insertions(+), 5 deletions(-) (limited to 'src/modules') diff --git a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp index c61b6ff3f..e10c7de56 100755 --- a/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp +++ b/src/modules/attitude_estimator_ekf/attitude_estimator_ekf_main.cpp @@ -64,6 +64,7 @@ #include #include +#include #include #include @@ -292,6 +293,9 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds float gyro_offsets[3] = { 0.0f, 0.0f, 0.0f }; unsigned offset_count = 0; + /* magnetic declination, in radians */ + float mag_decl = 0.0f; + /* rotation matrix for magnetic declination */ math::Matrix<3, 3> R_decl; R_decl.identity(); @@ -330,9 +334,6 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds /* update parameters */ parameters_update(&ekf_param_handles, &ekf_params); - - /* update mag declination rotation matrix */ - R_decl.from_euler(0.0f, 0.0f, ekf_params.mag_decl); } /* only run filter if sensor values changed */ @@ -345,6 +346,13 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds orb_check(sub_gps, &gps_updated); if (gps_updated) { orb_copy(ORB_ID(vehicle_gps_position), sub_gps, &gps); + + if (gps.eph_m < 20.0f && hrt_elapsed_time(&gps.timestamp_position) < 1000000) { + mag_decl = math::radians(get_mag_declination(gps.lat / 1e7f, gps.lon / 1e7f)); + + /* update mag declination rotation matrix */ + R_decl.from_euler(0.0f, 0.0f, mag_decl); + } } bool global_pos_updated; @@ -474,7 +482,15 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds parameters_update(&ekf_param_handles, &ekf_params); /* update mag declination rotation matrix */ - R_decl.from_euler(0.0f, 0.0f, ekf_params.mag_decl); + if (gps.eph_m < 20.0f && hrt_elapsed_time(&gps.timestamp_position) < 1000000) { + mag_decl = math::radians(get_mag_declination(gps.lat / 1e7f, gps.lon / 1e7f)); + + } else { + mag_decl = ekf_params.mag_decl; + } + + /* update mag declination rotation matrix */ + R_decl.from_euler(0.0f, 0.0f, mag_decl); x_aposteriori_k[0] = z_k[0]; x_aposteriori_k[1] = z_k[1]; @@ -522,7 +538,7 @@ const unsigned int loop_interval_alarm = 6500; // loop interval in microseconds att.roll = euler[0]; att.pitch = euler[1]; - att.yaw = euler[2] + ekf_params.mag_decl; + att.yaw = euler[2] + mag_decl; att.rollspeed = x_aposteriori[0]; att.pitchspeed = x_aposteriori[1]; -- cgit v1.2.3 From fbb3adde06e5ecf88a4c39e332a539fa12d173b3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 May 2014 16:04:02 +0200 Subject: mavlink app: Clean up allocations --- src/modules/mavlink/mavlink_commands.cpp | 29 +- src/modules/mavlink/mavlink_main.cpp | 112 +- src/modules/mavlink/mavlink_main.h | 10 +- src/modules/mavlink/mavlink_messages.cpp | 1928 +++++++++++----------- src/modules/mavlink/mavlink_messages.h | 15 +- src/modules/mavlink/mavlink_orb_subscription.cpp | 19 +- src/modules/mavlink/mavlink_orb_subscription.h | 18 +- src/modules/mavlink/mavlink_receiver.cpp | 1 - src/modules/mavlink/mavlink_stream.h | 22 +- 9 files changed, 1080 insertions(+), 1074 deletions(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_commands.cpp b/src/modules/mavlink/mavlink_commands.cpp index 1c1e097a4..5760d7512 100644 --- a/src/modules/mavlink/mavlink_commands.cpp +++ b/src/modules/mavlink/mavlink_commands.cpp @@ -43,7 +43,6 @@ MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel) { _cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command)); - _cmd = (struct vehicle_command_s *)_cmd_sub->get_data(); } MavlinkCommandsStream::~MavlinkCommandsStream() @@ -53,21 +52,23 @@ MavlinkCommandsStream::~MavlinkCommandsStream() void MavlinkCommandsStream::update(const hrt_abstime t) { - if (_cmd_sub->update(t)) { + struct vehicle_command_s cmd; + + if (_cmd_sub->update(t, &cmd)) { /* only send commands for other systems/components */ - if (_cmd->target_system != mavlink_system.sysid || _cmd->target_component != mavlink_system.compid) { + 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); + 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_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 6c97bfca7..340b20e1b 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -234,6 +234,11 @@ Mavlink::Mavlink() : _subscribe_to_stream_rate(0.0f), _flow_control_enabled(true), _message_buffer({}), + _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")) @@ -493,44 +498,39 @@ Mavlink::mavlink_dev_ioctl(struct file *filep, int cmd, unsigned long arg) void Mavlink::mavlink_update_system(void) { - static bool initialized = false; - static param_t param_system_id; - static param_t param_component_id; - static param_t param_system_type; - static param_t param_use_hil_gps; - if (!initialized) { - param_system_id = param_find("MAV_SYS_ID"); - param_component_id = param_find("MAV_COMP_ID"); - param_system_type = param_find("MAV_TYPE"); - param_use_hil_gps = param_find("MAV_USEHILGPS"); - initialized = true; + if (!_param_initialized) { + _param_system_id = param_find("MAV_SYS_ID"); + _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); + 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); + param_get(_param_component_id, &component_id); if (component_id > 0 && component_id < 255) { mavlink_system.compid = component_id; } int32_t system_type; - param_get(param_system_type, &system_type); + param_get(_param_system_type, &system_type); if (system_type >= 0 && system_type < MAV_TYPE_ENUM_END) { mavlink_system.type = system_type; } int32_t use_hil_gps; - param_get(param_use_hil_gps, &use_hil_gps); + param_get(_param_use_hil_gps, &use_hil_gps); _use_hil_gps = (bool)use_hil_gps; } @@ -791,7 +791,7 @@ void Mavlink::mavlink_pm_message_handler(const mavlink_channel_t chan, const mav case MAVLINK_MSG_ID_PARAM_REQUEST_LIST: { /* Start sending parameters */ mavlink_pm_start_queued_send(); - mavlink_missionlib_send_gcs_string("[mavlink pm] sending list"); + mavlink_missionlib_send_gcs_string("[pm] sending list"); } break; case MAVLINK_MSG_ID_PARAM_SET: { @@ -813,7 +813,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, "[mavlink pm] unknown: %s", name); + sprintf(buf, "[pm] unknown: %s", name); mavlink_missionlib_send_gcs_string(buf); } else { @@ -1001,8 +1001,6 @@ void Mavlink::mavlink_wpm_send_waypoint_current(uint16_t seq) } else { mavlink_missionlib_send_gcs_string("ERROR: wp index out of bounds"); - - if (_verbose) { warnx("ERROR: index out of bounds"); } } } @@ -1073,8 +1071,6 @@ void Mavlink::mavlink_wpm_send_waypoint_request(uint8_t sysid, uint8_t compid, u } else { mavlink_missionlib_send_gcs_string("ERROR: Waypoint index exceeds list capacity"); - - if (_verbose) { warnx("ERROR: Waypoint index exceeds list capacity"); } } } @@ -1105,8 +1101,6 @@ 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); } - _wpm->current_state = MAVLINK_WPM_STATE_IDLE; _wpm->current_partner_sysid = 0; _wpm->current_partner_compid = 0; @@ -1137,8 +1131,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) } else { mavlink_missionlib_send_gcs_string("REJ. WP CMD: curr partner id mismatch"); - - if (_verbose) { warnx("REJ. WP CMD: curr partner id mismatch"); } } break; @@ -1162,21 +1154,14 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) } else { mavlink_missionlib_send_gcs_string("IGN WP CURR CMD: Not in list"); - - if (_verbose) { warnx("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"); } - } } else { mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch"); - - if (_verbose) { warnx("REJ. WP CMD: target id mismatch"); } } break; @@ -1206,14 +1191,10 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) } else { mavlink_missionlib_send_gcs_string("IGN REQUEST LIST: Busy"); - - if (_verbose) { warnx("IGN REQUEST LIST: Busy"); } } } else { mavlink_missionlib_send_gcs_string("REJ. REQUEST LIST: target id mismatch"); - - if (_verbose) { warnx("REJ. REQUEST LIST: target id mismatch"); } } break; @@ -1230,8 +1211,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) 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; } @@ -1242,15 +1221,13 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) if (_wpm->current_state == MAVLINK_WPM_STATE_SENDLIST) { 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); } + if (_verbose) { warnx("Got ITEM_REQUEST of waypoint %u from %u changing to STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } _wpm->current_state = MAVLINK_WPM_STATE_SENDLIST_SENDWPS; } else { mavlink_missionlib_send_gcs_string("REJ. WP CMD: First id != 0"); - if (_verbose) { warnx("REJ. WP CMD: First id != 0"); } - break; } @@ -1258,17 +1235,15 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) if (wpr.seq == _wpm->current_wp_id) { - 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); } + if (_verbose) { warnx("Got ITEM_REQUEST of waypoint %u (again) from %u staying in STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } } else if (wpr.seq == _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); } + if (_verbose) { warnx("Got ITEM_REQUEST of waypoint %u from %u staying in STATE_SENDLIST_SENDWPS", wpr.seq, msg->sysid); } } 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); } - break; } @@ -1276,8 +1251,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) 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); } - break; } @@ -1291,7 +1264,7 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) } 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); } + mavlink_missionlib_send_gcs_string("ERROR: Waypoint out of bounds"); } @@ -1301,13 +1274,9 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); - 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); } - } else { mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch"); - - if (_verbose) { warnx("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH"); } } } @@ -1331,15 +1300,11 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) } 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"); } + mavlink_missionlib_send_gcs_string("WP COUNT 0"); 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; @@ -1353,25 +1318,17 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) if (_wpm->current_wp_id == 0) { mavlink_missionlib_send_gcs_string("WP CMD OK AGAIN"); - if (_verbose) { warnx("Got MAVLINK_MSG_ID_MISSION_ITEM_COUNT (%u) again from %u", wpc.count, msg->sysid); } - } else { - mavlink_missionlib_send_gcs_string("REJ. WP CMD: Busy"); - - 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 with WP"); } } else { mavlink_missionlib_send_gcs_string("IGN MISSION_COUNT CMD: Busy"); - - if (_verbose) { warnx("IGN MISSION_COUNT CMD: Busy"); } } } else { mavlink_missionlib_send_gcs_string("REJ. WP COUNT CMD: target id mismatch"); - - if (_verbose) { warnx("IGNORED WAYPOINT COUNT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH"); } } } break; @@ -1393,7 +1350,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) 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); break; } @@ -1401,12 +1357,11 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) if (wp.seq >= _wpm->current_count) { 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); + mavlink_missionlib_send_gcs_string("IGN: waypoint ID mismatch"); mavlink_wpm_send_waypoint_request(_wpm->current_partner_sysid, _wpm->current_partner_compid, _wpm->current_wp_id); break; } @@ -1473,8 +1428,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) } else { mavlink_missionlib_send_gcs_string("REJ. WP CMD: target id mismatch"); - - if (_verbose) { warnx("IGNORED WAYPOINT COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH"); } } break; @@ -1515,8 +1468,6 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) } else if (wpca.target_system == mavlink_system.sysid /*&& wpca.target_component == mavlink_wpm_comp_id */ && _wpm->current_state != MAVLINK_WPM_STATE_IDLE) { mavlink_missionlib_send_gcs_string("REJ. WP CLERR CMD: target id mismatch"); - - if (_verbose) { warnx("IGNORED WAYPOINT CLEAR COMMAND BECAUSE TARGET SYSTEM AND COMPONENT OR COMM PARTNER ID MISMATCH"); } } break; @@ -1535,8 +1486,7 @@ Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg) uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN]; uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg); - - mavlink_send_uart_bytes(_channel, missionlib_msg_buf, len); + mavlink_send_uart_bytes(_channel, buf, len); } @@ -1619,6 +1569,7 @@ Mavlink::configure_stream(const char *stream_name, const float rate) if (interval > 0) { /* search for stream with specified name in supported streams list */ for (unsigned int i = 0; streams_list[i] != nullptr; i++) { + if (strcmp(stream_name, streams_list[i]->get_name()) == 0) { /* create new instance */ stream = streams_list[i]->new_instance(); @@ -1924,7 +1875,7 @@ Mavlink::task_main(int argc, char *argv[]) /* if we are passing on mavlink messages, we need to prepare a buffer for this instance */ if (_passing_on) { /* initialize message buffer if multiplexing is on */ - if (OK != message_buffer_init(500)) { + if (OK != message_buffer_init(300)) { errx(1, "can't allocate message buffer, exiting"); } @@ -1956,7 +1907,8 @@ Mavlink::task_main(int argc, char *argv[]) MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update)); MavlinkOrbSubscription *status_sub = add_orb_subscription(ORB_ID(vehicle_status)); - struct vehicle_status_s *status = (struct vehicle_status_s *) status_sub->get_data(); + struct vehicle_status_s status; + status_sub->update(0, &status); MavlinkCommandsStream commands_stream(this, _channel); @@ -2013,14 +1965,14 @@ Mavlink::task_main(int argc, char *argv[]) hrt_abstime t = hrt_absolute_time(); - if (param_sub->update(t)) { + if (param_sub->update(t, nullptr)) { /* parameters updated */ mavlink_update_system(); } - if (status_sub->update(t)) { + if (status_sub->update(t, &status)) { /* switch HIL mode if required */ - set_hil_enabled(status->hil_state == HIL_STATE_ON); + set_hil_enabled(status.hil_state == HIL_STATE_ON); } /* update commands stream */ diff --git a/src/modules/mavlink/mavlink_main.h b/src/modules/mavlink/mavlink_main.h index c7a7d32f8..1f0445cb6 100644 --- a/src/modules/mavlink/mavlink_main.h +++ b/src/modules/mavlink/mavlink_main.h @@ -278,11 +278,15 @@ private: int size; char *data; }; - mavlink_message_buffer _message_buffer; - - pthread_mutex_t _message_buffer_mutex; + mavlink_message_buffer _message_buffer; + pthread_mutex_t _message_buffer_mutex; + bool _param_initialized; + param_t _param_system_id; + param_t _param_component_id; + param_t _param_system_type; + param_t _param_use_hil_gps; /** * Send one parameter. diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 79dd88657..4bb827116 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -74,6 +74,8 @@ #include #include +#include + #include "mavlink_messages.h" @@ -189,42 +191,51 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set class MavlinkStreamHeartbeat : public MavlinkStream { public: - const char *get_name() + + ~MavlinkStreamHeartbeat() {}; + + const char *get_name() const + { + return MavlinkStreamHeartbeat::get_name_static(); + } + + static const char *get_name_static() { return "HEARTBEAT"; } - MavlinkStream *new_instance() + static MavlinkStream *new_instance() { return new MavlinkStreamHeartbeat(); } private: MavlinkOrbSubscription *status_sub; - struct vehicle_status_s *status; - MavlinkOrbSubscription *pos_sp_triplet_sub; - struct position_setpoint_triplet_s *pos_sp_triplet; + protected: + + explicit MavlinkStreamHeartbeat() {}; + void subscribe(Mavlink *mavlink) { status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); - status = (struct vehicle_status_s *)status_sub->get_data(); - pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); - pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data(); } void send(const hrt_abstime t) { - (void)status_sub->update(t); - (void)pos_sp_triplet_sub->update(t); + struct vehicle_status_s status; + struct position_setpoint_triplet_s pos_sp_triplet; + + (void)status_sub->update(t, &status); + (void)pos_sp_triplet_sub->update(t, &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); + get_mavlink_mode_state(&status, &pos_sp_triplet, &mavlink_state, &mavlink_base_mode, &mavlink_custom_mode); mavlink_msg_heartbeat_send(_channel, mavlink_system.type, @@ -240,12 +251,19 @@ protected: class MavlinkStreamSysStatus : public MavlinkStream { public: - const char *get_name() + ~MavlinkStreamSysStatus() {}; + + const char *get_name() const + { + return MavlinkStreamSysStatus::get_name_static(); + } + + static const char *get_name_static () { return "SYS_STATUS"; } - MavlinkStream *new_instance() + static MavlinkStream *new_instance() { return new MavlinkStreamSysStatus(); } @@ -255,29 +273,31 @@ private: struct vehicle_status_s *status; protected: + explicit MavlinkStreamSysStatus() {}; + void subscribe(Mavlink *mavlink) { status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); - status = (struct vehicle_status_s *)status_sub->get_data(); } void send(const hrt_abstime t) { - status_sub->update(t); + struct vehicle_status_s status; + (void)status_sub->update(t, &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 * 1000.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); + 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 * 1000.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); } }; @@ -285,23 +305,25 @@ protected: class MavlinkStreamHighresIMU : public MavlinkStream { public: - MavlinkStreamHighresIMU() : MavlinkStream(), accel_timestamp(0), gyro_timestamp(0), mag_timestamp(0), baro_timestamp(0) + ~MavlinkStreamHighresIMU(); + + const char *get_name() const { + return MavlinkStreamHighresIMU::get_name_static(); } - const char *get_name() + static const char *get_name_static() { return "HIGHRES_IMU"; } - MavlinkStream *new_instance() + static MavlinkStream *new_instance() { return new MavlinkStreamHighresIMU(); } private: MavlinkOrbSubscription *sensor_sub; - struct sensor_combined_s *sensor; uint64_t accel_timestamp; uint64_t gyro_timestamp; @@ -309,48 +331,52 @@ private: uint64_t baro_timestamp; protected: + explicit MavlinkStreamHighresIMU() : MavlinkStream(), 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)); - sensor = (struct sensor_combined_s *)sensor_sub->get_data(); } void send(const hrt_abstime t) { - if (sensor_sub->update(t)) { + struct sensor_combined_s sensor; + if (sensor_sub->update(t, &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_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, + 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); } } @@ -360,12 +386,17 @@ protected: class MavlinkStreamAttitude : public MavlinkStream { public: - const char *get_name() + const char *get_name() const + { + return MavlinkStreamAttitude::get_name_static(); + } + + static const char *get_name_static() { return "ATTITUDE"; } - MavlinkStream *new_instance() + static MavlinkStream *new_instance() { return new MavlinkStreamAttitude(); } @@ -378,16 +409,17 @@ protected: void subscribe(Mavlink *mavlink) { att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); - att = (struct vehicle_attitude_s *)att_sub->get_data(); } void send(const hrt_abstime t) { - if (att_sub->update(t)) { + struct vehicle_attitude_s att; + + if (att_sub->update(t, &att)) { mavlink_msg_attitude_send(_channel, - att->timestamp / 1000, - att->roll, att->pitch, att->yaw, - att->rollspeed, att->pitchspeed, att->yawspeed); + att.timestamp / 1000, + att.roll, att.pitch, att.yaw, + att.rollspeed, att.pitchspeed, att.yawspeed); } } }; @@ -396,39 +428,44 @@ protected: class MavlinkStreamAttitudeQuaternion : public MavlinkStream { public: - const char *get_name() + const char *get_name() const + { + return MavlinkStreamAttitudeQuaternion::get_name_static(); + } + + static const char *get_name_static() { return "ATTITUDE_QUATERNION"; } - MavlinkStream *new_instance() + static MavlinkStream *new_instance() { return new MavlinkStreamAttitudeQuaternion(); } private: MavlinkOrbSubscription *att_sub; - struct vehicle_attitude_s *att; protected: void subscribe(Mavlink *mavlink) { att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); - att = (struct vehicle_attitude_s *)att_sub->get_data(); } void send(const hrt_abstime t) { - if (att_sub->update(t)) { + struct vehicle_attitude_s att; + + if (att_sub->update(t, &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); + att.timestamp / 1000, + att.q[0], + att.q[1], + att.q[2], + att.q[3], + att.rollspeed, + att.pitchspeed, + att.yawspeed); } } }; @@ -437,12 +474,18 @@ protected: class MavlinkStreamVFRHUD : public MavlinkStream { public: - const char *get_name() + + const char *get_name() const + { + return MavlinkStreamVFRHUD::get_name_static(); + } + + static const char *get_name_static() { return "VFR_HUD"; } - MavlinkStream *new_instance() + static MavlinkStream *new_instance() { return new MavlinkStreamVFRHUD(); } @@ -467,41 +510,38 @@ protected: void subscribe(Mavlink *mavlink) { att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); - att = (struct vehicle_attitude_s *)att_sub->get_data(); - pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); - pos = (struct vehicle_global_position_s *)pos_sub->get_data(); - armed_sub = mavlink->add_orb_subscription(ORB_ID(actuator_armed)); - armed = (struct actuator_armed_s *)armed_sub->get_data(); - act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_controls_0)); - act = (struct actuator_controls_s *)act_sub->get_data(); - airspeed_sub = mavlink->add_orb_subscription(ORB_ID(airspeed)); - airspeed = (struct airspeed_s *)airspeed_sub->get_data(); } void send(const hrt_abstime t) { - bool updated = att_sub->update(t); - updated |= pos_sub->update(t); - updated |= armed_sub->update(t); - updated |= act_sub->update(t); - updated |= airspeed_sub->update(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(t, &att); + updated |= pos_sub->update(t, &pos); + updated |= armed_sub->update(t, &armed); + updated |= act_sub->update(t, &act); + updated |= airspeed_sub->update(t, &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; + 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, + airspeed.true_airspeed_m_s, groundspeed, heading, throttle, - pos->alt, - -pos->vel_d); + pos.alt, + pos.vel_d); } } }; @@ -510,12 +550,17 @@ protected: class MavlinkStreamGPSRawInt : public MavlinkStream { public: - const char *get_name() + const char *get_name() const + { + return MavlinkStreamGPSRawInt::get_name_static(); + } + + static const char *get_name_static() { return "GPS_RAW_INT"; } - MavlinkStream *new_instance() + static MavlinkStream *new_instance() { return new MavlinkStreamGPSRawInt(); } @@ -528,864 +573,865 @@ protected: void subscribe(Mavlink *mavlink) { gps_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position)); - gps = (struct vehicle_gps_position_s *)gps_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (gps_sub->update(t)) { - 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_m), - 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); - } - } -}; - - -class MavlinkStreamGlobalPositionInt : public MavlinkStream -{ -public: - const char *get_name() - { - return "GLOBAL_POSITION_INT"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamGlobalPositionInt(); - } - -private: - MavlinkOrbSubscription *pos_sub; - struct vehicle_global_position_s *pos; - - MavlinkOrbSubscription *home_sub; - struct home_position_s *home; - -protected: - void subscribe(Mavlink *mavlink) - { - pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); - pos = (struct vehicle_global_position_s *)pos_sub->get_data(); - - home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); - home = (struct home_position_s *)home_sub->get_data(); - } - - void send(const hrt_abstime t) - { - bool updated = pos_sub->update(t); - updated |= home_sub->update(t); - - 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() - { - return "LOCAL_POSITION_NED"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamLocalPositionNED(); - } - -private: - MavlinkOrbSubscription *pos_sub; - struct vehicle_local_position_s *pos; - -protected: - void subscribe(Mavlink *mavlink) - { - pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position)); - pos = (struct vehicle_local_position_s *)pos_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (pos_sub->update(t)) { - 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() - { - return "VICON_POSITION_ESTIMATE"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamViconPositionEstimate(); - } - -private: - MavlinkOrbSubscription *pos_sub; - struct vehicle_vicon_position_s *pos; - -protected: - void subscribe(Mavlink *mavlink) - { - pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position)); - pos = (struct vehicle_vicon_position_s *)pos_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (pos_sub->update(t)) { - 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() - { - return "GPS_GLOBAL_ORIGIN"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamGPSGlobalOrigin(); - } - -private: - MavlinkOrbSubscription *home_sub; - struct home_position_s *home; - -protected: - void subscribe(Mavlink *mavlink) - { - home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); - home = (struct home_position_s *)home_sub->get_data(); - } - - 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()) { - home_sub->update(t); - - mavlink_msg_gps_global_origin_send(_channel, - (int32_t)(home->lat * 1e7), - (int32_t)(home->lon * 1e7), - (int32_t)(home->alt) * 1000.0f); - } - } -}; - - -class MavlinkStreamServoOutputRaw : public MavlinkStream -{ -public: - MavlinkStreamServoOutputRaw(unsigned int n) : MavlinkStream(), _n(n) - { - sprintf(_name, "SERVO_OUTPUT_RAW_%d", _n); - } - - const char *get_name() - { - return _name; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamServoOutputRaw(_n); - } - -private: - MavlinkOrbSubscription *act_sub; - struct actuator_outputs_s *act; - - char _name[20]; - unsigned int _n; - -protected: - 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]); - act = (struct actuator_outputs_s *)act_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (act_sub->update(t)) { - 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() - { - return "HIL_CONTROLS"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamHILControls(); - } - -private: - MavlinkOrbSubscription *status_sub; - struct vehicle_status_s *status; - - MavlinkOrbSubscription *pos_sp_triplet_sub; - struct position_setpoint_triplet_s *pos_sp_triplet; - - MavlinkOrbSubscription *act_sub; - struct actuator_outputs_s *act; - -protected: - void subscribe(Mavlink *mavlink) - { - status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); - status = (struct vehicle_status_s *)status_sub->get_data(); - - pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); - pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data(); - - act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0)); - act = (struct actuator_outputs_s *)act_sub->get_data(); - } - - void send(const hrt_abstime t) - { - bool updated = act_sub->update(t); - (void)pos_sp_triplet_sub->update(t); - (void)status_sub->update(t); - - 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); - - 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 */ - unsigned n; - - switch (mavlink_system.type) { - case MAV_TYPE_QUADROTOR: - n = 4; - break; - - case MAV_TYPE_HEXAROTOR: - n = 6; - break; - - default: - n = 8; - 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 */ - out[i] = (act->output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); - - } else { - /* send 0 when disarmed */ - out[i] = 0.0f; - } - - } else { - out[i] = -1.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; - - for (unsigned i = 0; i < 8; i++) { - if (i != 3) { - /* scale fake 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 */ - 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() - { - return "GLOBAL_POSITION_SETPOINT_INT"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamGlobalPositionSetpointInt(); - } - -private: - MavlinkOrbSubscription *pos_sp_triplet_sub; - struct position_setpoint_triplet_s *pos_sp_triplet; - -protected: - void subscribe(Mavlink *mavlink) - { - pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); - pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data(); } void send(const hrt_abstime t) { - if (pos_sp_triplet_sub->update(t)) { - 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() - { - return "LOCAL_POSITION_SETPOINT"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamLocalPositionSetpoint(); - } - -private: - MavlinkOrbSubscription *pos_sp_sub; - struct vehicle_local_position_setpoint_s *pos_sp; - -protected: - void subscribe(Mavlink *mavlink) - { - pos_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint)); - pos_sp = (struct vehicle_local_position_setpoint_s *)pos_sp_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (pos_sp_sub->update(t)) { - 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() - { - return "ROLL_PITCH_YAW_THRUST_SETPOINT"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamRollPitchYawThrustSetpoint(); - } - -private: - MavlinkOrbSubscription *att_sp_sub; - struct vehicle_attitude_setpoint_s *att_sp; - -protected: - void subscribe(Mavlink *mavlink) - { - att_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint)); - att_sp = (struct vehicle_attitude_setpoint_s *)att_sp_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (att_sp_sub->update(t)) { - 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() - { - return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamRollPitchYawRatesThrustSetpoint(); - } - -private: - MavlinkOrbSubscription *att_rates_sp_sub; - struct vehicle_rates_setpoint_s *att_rates_sp; - -protected: - void subscribe(Mavlink *mavlink) - { - att_rates_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint)); - att_rates_sp = (struct vehicle_rates_setpoint_s *)att_rates_sp_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (att_rates_sp_sub->update(t)) { - 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() - { - return "RC_CHANNELS_RAW"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamRCChannelsRaw(); - } - -private: - MavlinkOrbSubscription *rc_sub; - struct rc_input_values *rc; - -protected: - void subscribe(Mavlink *mavlink) - { - rc_sub = mavlink->add_orb_subscription(ORB_ID(input_rc)); - rc = (struct rc_input_values *)rc_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (rc_sub->update(t)) { - const unsigned port_width = 8; - - 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); - } - } - } -}; - - -class MavlinkStreamManualControl : public MavlinkStream -{ -public: - const char *get_name() - { - return "MANUAL_CONTROL"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamManualControl(); - } - -private: - MavlinkOrbSubscription *manual_sub; - struct manual_control_setpoint_s *manual; - -protected: - void subscribe(Mavlink *mavlink) - { - manual_sub = mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); - manual = (struct manual_control_setpoint_s *)manual_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (manual_sub->update(t)) { - mavlink_msg_manual_control_send(_channel, - mavlink_system.sysid, - manual->x * 1000, - manual->y * 1000, - manual->z * 1000, - manual->r * 1000, - 0); - } - } -}; + struct vehicle_gps_position_s gps; - -class MavlinkStreamOpticalFlow : public MavlinkStream -{ -public: - const char *get_name() - { - return "OPTICAL_FLOW"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamOpticalFlow(); - } - -private: - MavlinkOrbSubscription *flow_sub; - struct optical_flow_s *flow; - -protected: - void subscribe(Mavlink *mavlink) - { - flow_sub = mavlink->add_orb_subscription(ORB_ID(optical_flow)); - flow = (struct optical_flow_s *)flow_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (flow_sub->update(t)) { - 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() - { - return "ATTITUDE_CONTROLS"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamAttitudeControls(); - } - -private: - MavlinkOrbSubscription *att_ctrl_sub; - struct actuator_controls_s *att_ctrl; - -protected: - void subscribe(Mavlink *mavlink) - { - att_ctrl_sub = mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); - att_ctrl = (struct actuator_controls_s *)att_ctrl_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (att_ctrl_sub->update(t)) { - /* 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() - { - return "NAMED_VALUE_FLOAT"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamNamedValueFloat(); - } - -private: - MavlinkOrbSubscription *debug_sub; - struct debug_key_value_s *debug; - -protected: - void subscribe(Mavlink *mavlink) - { - debug_sub = mavlink->add_orb_subscription(ORB_ID(debug_key_value)); - debug = (struct debug_key_value_s *)debug_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (debug_sub->update(t)) { - /* 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() - { - return "CAMERA_CAPTURE"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamCameraCapture(); - } - -private: - MavlinkOrbSubscription *status_sub; - struct vehicle_status_s *status; - -protected: - void subscribe(Mavlink *mavlink) - { - status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); - status = (struct vehicle_status_s *)status_sub->get_data(); - } - - void send(const hrt_abstime t) - { - (void)status_sub->update(t); - - 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); + if (gps_sub->update(t, &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_m), + 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); } } }; -class MavlinkStreamDistanceSensor : public MavlinkStream -{ -public: - const char *get_name() - { - return "DISTANCE_SENSOR"; - } - - MavlinkStream *new_instance() - { - return new MavlinkStreamDistanceSensor(); - } - -private: - MavlinkOrbSubscription *range_sub; - struct range_finder_report *range; - -protected: - void subscribe(Mavlink *mavlink) - { - range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder)); - range = (struct range_finder_report *)range_sub->get_data(); - } - - void send(const hrt_abstime t) - { - if (range_sub->update(t)) { - - 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); - } - } -}; -MavlinkStream *streams_list[] = { - new MavlinkStreamHeartbeat(), - new MavlinkStreamSysStatus(), - new MavlinkStreamHighresIMU(), - new MavlinkStreamAttitude(), - new MavlinkStreamAttitudeQuaternion(), - new MavlinkStreamVFRHUD(), - new MavlinkStreamGPSRawInt(), - new MavlinkStreamGlobalPositionInt(), - new MavlinkStreamLocalPositionNED(), - new MavlinkStreamGPSGlobalOrigin(), - new MavlinkStreamServoOutputRaw(0), - new MavlinkStreamServoOutputRaw(1), - new MavlinkStreamServoOutputRaw(2), - new MavlinkStreamServoOutputRaw(3), - new MavlinkStreamHILControls(), - new MavlinkStreamGlobalPositionSetpointInt(), - new MavlinkStreamLocalPositionSetpoint(), - new MavlinkStreamRollPitchYawThrustSetpoint(), - new MavlinkStreamRollPitchYawRatesThrustSetpoint(), - new MavlinkStreamRCChannelsRaw(), - new MavlinkStreamManualControl(), - new MavlinkStreamOpticalFlow(), - new MavlinkStreamAttitudeControls(), - new MavlinkStreamNamedValueFloat(), - new MavlinkStreamCameraCapture(), - new MavlinkStreamDistanceSensor(), - new MavlinkStreamViconPositionEstimate(), +// class MavlinkStreamGlobalPositionInt : public MavlinkStream +// { +// public: +// const char *get_name() +// { +// return "GLOBAL_POSITION_INT"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamGlobalPositionInt(); +// } + +// private: +// MavlinkOrbSubscription *pos_sub; +// struct vehicle_global_position_s *pos; + +// MavlinkOrbSubscription *home_sub; +// struct home_position_s *home; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); +// pos = (struct vehicle_global_position_s *)pos_sub->get_data(); + +// home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); +// home = (struct home_position_s *)home_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// bool updated = pos_sub->update(t); +// updated |= home_sub->update(t); + +// 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() +// { +// return "LOCAL_POSITION_NED"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamLocalPositionNED(); +// } + +// private: +// MavlinkOrbSubscription *pos_sub; +// struct vehicle_local_position_s *pos; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position)); +// pos = (struct vehicle_local_position_s *)pos_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (pos_sub->update(t)) { +// 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() +// { +// return "VICON_POSITION_ESTIMATE"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamViconPositionEstimate(); +// } + +// private: +// MavlinkOrbSubscription *pos_sub; +// struct vehicle_vicon_position_s *pos; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position)); +// pos = (struct vehicle_vicon_position_s *)pos_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (pos_sub->update(t)) { +// 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() +// { +// return "GPS_GLOBAL_ORIGIN"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamGPSGlobalOrigin(); +// } + +// private: +// MavlinkOrbSubscription *home_sub; +// struct home_position_s *home; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); +// home = (struct home_position_s *)home_sub->get_data(); +// } + +// 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()) { +// home_sub->update(t); + +// mavlink_msg_gps_global_origin_send(_channel, +// (int32_t)(home->lat * 1e7), +// (int32_t)(home->lon * 1e7), +// (int32_t)(home->alt) * 1000.0f); +// } +// } +// }; + + +// class MavlinkStreamServoOutputRaw : public MavlinkStream +// { +// public: +// MavlinkStreamServoOutputRaw(unsigned int n) : MavlinkStream(), _n(n) +// { +// sprintf(_name, "SERVO_OUTPUT_RAW_%d", _n); +// } + +// const char *get_name() +// { +// return _name; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamServoOutputRaw(_n); +// } + +// private: +// MavlinkOrbSubscription *act_sub; +// struct actuator_outputs_s *act; + +// char _name[20]; +// unsigned int _n; + +// protected: +// 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]); +// act = (struct actuator_outputs_s *)act_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (act_sub->update(t)) { +// 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() +// { +// return "HIL_CONTROLS"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamHILControls(); +// } + +// private: +// MavlinkOrbSubscription *status_sub; +// struct vehicle_status_s *status; + +// MavlinkOrbSubscription *pos_sp_triplet_sub; +// struct position_setpoint_triplet_s *pos_sp_triplet; + +// MavlinkOrbSubscription *act_sub; +// struct actuator_outputs_s *act; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); +// status = (struct vehicle_status_s *)status_sub->get_data(); + +// pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); +// pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data(); + +// act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0)); +// act = (struct actuator_outputs_s *)act_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// bool updated = act_sub->update(t); +// (void)pos_sp_triplet_sub->update(t); +// (void)status_sub->update(t); + +// 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); + +// 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 */ +// unsigned n; + +// switch (mavlink_system.type) { +// case MAV_TYPE_QUADROTOR: +// n = 4; +// break; + +// case MAV_TYPE_HEXAROTOR: +// n = 6; +// break; + +// default: +// n = 8; +// 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 */ +// out[i] = (act->output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); + +// } else { +// /* send 0 when disarmed */ +// out[i] = 0.0f; +// } + +// } else { +// out[i] = -1.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; + +// for (unsigned i = 0; i < 8; i++) { +// if (i != 3) { +// /* scale fake 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 */ +// 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() +// { +// return "GLOBAL_POSITION_SETPOINT_INT"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamGlobalPositionSetpointInt(); +// } + +// private: +// MavlinkOrbSubscription *pos_sp_triplet_sub; +// struct position_setpoint_triplet_s *pos_sp_triplet; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); +// pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (pos_sp_triplet_sub->update(t)) { +// 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() +// { +// return "LOCAL_POSITION_SETPOINT"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamLocalPositionSetpoint(); +// } + +// private: +// MavlinkOrbSubscription *pos_sp_sub; +// struct vehicle_local_position_setpoint_s *pos_sp; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// pos_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint)); +// pos_sp = (struct vehicle_local_position_setpoint_s *)pos_sp_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (pos_sp_sub->update(t)) { +// 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() +// { +// return "ROLL_PITCH_YAW_THRUST_SETPOINT"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamRollPitchYawThrustSetpoint(); +// } + +// private: +// MavlinkOrbSubscription *att_sp_sub; +// struct vehicle_attitude_setpoint_s *att_sp; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// att_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint)); +// att_sp = (struct vehicle_attitude_setpoint_s *)att_sp_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (att_sp_sub->update(t)) { +// 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() +// { +// return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamRollPitchYawRatesThrustSetpoint(); +// } + +// private: +// MavlinkOrbSubscription *att_rates_sp_sub; +// struct vehicle_rates_setpoint_s *att_rates_sp; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// att_rates_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint)); +// att_rates_sp = (struct vehicle_rates_setpoint_s *)att_rates_sp_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (att_rates_sp_sub->update(t)) { +// 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() +// { +// return "RC_CHANNELS_RAW"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamRCChannelsRaw(); +// } + +// private: +// MavlinkOrbSubscription *rc_sub; +// struct rc_input_values *rc; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// rc_sub = mavlink->add_orb_subscription(ORB_ID(input_rc)); +// rc = (struct rc_input_values *)rc_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (rc_sub->update(t)) { +// const unsigned port_width = 8; + +// 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); +// } +// } +// } +// }; + + +// class MavlinkStreamManualControl : public MavlinkStream +// { +// public: +// const char *get_name() +// { +// return "MANUAL_CONTROL"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamManualControl(); +// } + +// private: +// MavlinkOrbSubscription *manual_sub; +// struct manual_control_setpoint_s *manual; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// manual_sub = mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); +// manual = (struct manual_control_setpoint_s *)manual_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (manual_sub->update(t)) { +// 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() +// { +// return "OPTICAL_FLOW"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamOpticalFlow(); +// } + +// private: +// MavlinkOrbSubscription *flow_sub; +// struct optical_flow_s *flow; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// flow_sub = mavlink->add_orb_subscription(ORB_ID(optical_flow)); +// flow = (struct optical_flow_s *)flow_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (flow_sub->update(t)) { +// 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() +// { +// return "ATTITUDE_CONTROLS"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamAttitudeControls(); +// } + +// private: +// MavlinkOrbSubscription *att_ctrl_sub; +// struct actuator_controls_s *att_ctrl; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// att_ctrl_sub = mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); +// att_ctrl = (struct actuator_controls_s *)att_ctrl_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (att_ctrl_sub->update(t)) { +// /* 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() +// { +// return "NAMED_VALUE_FLOAT"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamNamedValueFloat(); +// } + +// private: +// MavlinkOrbSubscription *debug_sub; +// struct debug_key_value_s *debug; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// debug_sub = mavlink->add_orb_subscription(ORB_ID(debug_key_value)); +// debug = (struct debug_key_value_s *)debug_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (debug_sub->update(t)) { +// /* 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() +// { +// return "CAMERA_CAPTURE"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamCameraCapture(); +// } + +// private: +// MavlinkOrbSubscription *status_sub; +// struct vehicle_status_s *status; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); +// status = (struct vehicle_status_s *)status_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// (void)status_sub->update(t); + +// 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() +// { +// return "DISTANCE_SENSOR"; +// } + +// MavlinkStream *new_instance() +// { +// return new MavlinkStreamDistanceSensor(); +// } + +// private: +// MavlinkOrbSubscription *range_sub; +// struct range_finder_report *range; + +// protected: +// void subscribe(Mavlink *mavlink) +// { +// range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder)); +// range = (struct range_finder_report *)range_sub->get_data(); +// } + +// void send(const hrt_abstime t) +// { +// if (range_sub->update(t)) { + +// 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 MavlinkStreamGlobalPositionInt(), + // new MavlinkStreamLocalPositionNED(), + // new MavlinkStreamGPSGlobalOrigin(), + // new MavlinkStreamServoOutputRaw(0), + // new MavlinkStreamServoOutputRaw(1), + // new MavlinkStreamServoOutputRaw(2), + // new MavlinkStreamServoOutputRaw(3), + // new MavlinkStreamHILControls(), + // new MavlinkStreamGlobalPositionSetpointInt(), + // new MavlinkStreamLocalPositionSetpoint(), + // new MavlinkStreamRollPitchYawThrustSetpoint(), + // new MavlinkStreamRollPitchYawRatesThrustSetpoint(), + // new MavlinkStreamRCChannelsRaw(), + // new MavlinkStreamManualControl(), + // new MavlinkStreamOpticalFlow(), + // new MavlinkStreamAttitudeControls(), + // new MavlinkStreamNamedValueFloat(), + // new MavlinkStreamCameraCapture(), + // new MavlinkStreamDistanceSensor(), + // new MavlinkStreamViconPositionEstimate(), nullptr }; diff --git a/src/modules/mavlink/mavlink_messages.h b/src/modules/mavlink/mavlink_messages.h index b8823263a..ee64d0e42 100644 --- a/src/modules/mavlink/mavlink_messages.h +++ b/src/modules/mavlink/mavlink_messages.h @@ -43,6 +43,19 @@ #include "mavlink_stream.h" -extern MavlinkStream *streams_list[]; +class StreamListItem { + +public: + MavlinkStream* (*new_instance)(); + const char* (*get_name)(); + + StreamListItem(MavlinkStream* (*inst)(), const char* (*name)()) : + new_instance(inst), + get_name(name) {}; + + ~StreamListItem() {}; +}; + +extern StreamListItem *streams_list[]; #endif /* MAVLINK_MESSAGES_H_ */ diff --git a/src/modules/mavlink/mavlink_orb_subscription.cpp b/src/modules/mavlink/mavlink_orb_subscription.cpp index d432edd2b..0a23fb01e 100644 --- a/src/modules/mavlink/mavlink_orb_subscription.cpp +++ b/src/modules/mavlink/mavlink_orb_subscription.cpp @@ -53,30 +53,21 @@ MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic) : _last_check(0), next(nullptr) { - _data = malloc(topic->o_size); - memset(_data, 0, topic->o_size); } MavlinkOrbSubscription::~MavlinkOrbSubscription() { close(_fd); - free(_data); } -const orb_id_t -MavlinkOrbSubscription::get_topic() +orb_id_t +MavlinkOrbSubscription::get_topic() const { return _topic; } -void * -MavlinkOrbSubscription::get_data() -{ - return _data; -} - bool -MavlinkOrbSubscription::update(const hrt_abstime t) +MavlinkOrbSubscription::update(const hrt_abstime t, void* data) { if (_last_check == t) { /* already checked right now, return result of the check */ @@ -86,8 +77,8 @@ MavlinkOrbSubscription::update(const hrt_abstime t) _last_check = t; orb_check(_fd, &_updated); - if (_updated) { - orb_copy(_topic, _fd, _data); + if (_updated && data) { + orb_copy(_topic, _fd, data); _published = true; return true; } diff --git a/src/modules/mavlink/mavlink_orb_subscription.h b/src/modules/mavlink/mavlink_orb_subscription.h index 5c6543e81..abd4031bd 100644 --- a/src/modules/mavlink/mavlink_orb_subscription.h +++ b/src/modules/mavlink/mavlink_orb_subscription.h @@ -48,12 +48,12 @@ class MavlinkOrbSubscription { public: - MavlinkOrbSubscription *next; /*< pointer to next subscription in list */ + MavlinkOrbSubscription *next; ///< pointer to next subscription in list MavlinkOrbSubscription(const orb_id_t topic); ~MavlinkOrbSubscription(); - bool update(const hrt_abstime t); + bool update(const hrt_abstime t, void* data); /** * Check if the topic has been published. @@ -62,16 +62,14 @@ public: * @return true if the topic has been published at least once. */ bool is_published(); - void *get_data(); - const orb_id_t get_topic(); + orb_id_t get_topic() const; private: - const orb_id_t _topic; /*< topic metadata */ - int _fd; /*< subscription handle */ - bool _published; /*< topic was ever published */ - void *_data; /*< pointer to data buffer */ - hrt_abstime _last_check; /*< time of last check */ - bool _updated; /*< updated on last check */ + const orb_id_t _topic; ///< topic metadata + int _fd; ///< subscription handle + bool _published; ///< topic was ever published + hrt_abstime _last_check; ///< time of last check + bool _updated; ///< updated on last check }; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 72b9ee83a..666b3a8cd 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -950,7 +950,6 @@ MavlinkReceiver::receive_start(Mavlink *parent) (void)pthread_attr_setschedparam(&receiveloop_attr, ¶m); pthread_attr_setstacksize(&receiveloop_attr, 2900); - pthread_t thread; pthread_create(&thread, &receiveloop_attr, MavlinkReceiver::start_helper, (void *)parent); diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h index def40d9ad..eb881edd7 100644 --- a/src/modules/mavlink/mavlink_stream.h +++ b/src/modules/mavlink/mavlink_stream.h @@ -50,14 +50,6 @@ class MavlinkStream; class MavlinkStream { -private: - hrt_abstime _last_sent; - -protected: - mavlink_channel_t _channel; - unsigned int _interval; - - virtual void send(const hrt_abstime t) = 0; public: MavlinkStream *next; @@ -67,9 +59,19 @@ public: void set_interval(const unsigned int interval); void set_channel(mavlink_channel_t channel); int update(const hrt_abstime t); - virtual MavlinkStream *new_instance() = 0; + static MavlinkStream *new_instance(); + static const char *get_name_static(); virtual void subscribe(Mavlink *mavlink) = 0; - virtual const char *get_name() = 0; + virtual const char *get_name() const = 0; + +protected: + mavlink_channel_t _channel; + unsigned int _interval; + + virtual void send(const hrt_abstime t) = 0; + +private: + hrt_abstime _last_sent; }; -- cgit v1.2.3 From 7926a1f8aed851d8ac22538279c11660dc645f20 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 13 May 2014 18:22:03 +0200 Subject: Converted streams to new API, saving a bunch of RAM --- src/modules/mavlink/mavlink_messages.cpp | 382 +++++++++++++++++-------------- 1 file changed, 212 insertions(+), 170 deletions(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 4bb827116..3a82f1f05 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -596,55 +596,57 @@ protected: }; -// class MavlinkStreamGlobalPositionInt : public MavlinkStream -// { -// public: -// const char *get_name() -// { -// return "GLOBAL_POSITION_INT"; -// } +class MavlinkStreamGlobalPositionInt : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamGlobalPositionInt::get_name_static(); + } -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamGlobalPositionInt(); -// } + static const char *get_name_static() + { + return "GLOBAL_POSITION_INT"; + } -// private: -// MavlinkOrbSubscription *pos_sub; -// struct vehicle_global_position_s *pos; + static MavlinkStream *new_instance() + { + return new MavlinkStreamGlobalPositionInt(); + } -// MavlinkOrbSubscription *home_sub; -// struct home_position_s *home; +private: + MavlinkOrbSubscription *pos_sub; + MavlinkOrbSubscription *home_sub; -// protected: -// void subscribe(Mavlink *mavlink) -// { -// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); -// pos = (struct vehicle_global_position_s *)pos_sub->get_data(); +protected: + 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)); + } -// home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); -// home = (struct home_position_s *)home_sub->get_data(); -// } + void send(const hrt_abstime t) + { + struct vehicle_global_position_s pos; + struct home_position_s home; -// void send(const hrt_abstime t) -// { -// bool updated = pos_sub->update(t); -// updated |= home_sub->update(t); - -// 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); -// } -// } -// }; + bool updated = pos_sub->update(t, &pos); + updated |= home_sub->update(t, &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 @@ -675,13 +677,13 @@ protected: // { // if (pos_sub->update(t)) { // mavlink_msg_local_position_ned_send(_channel, -// pos->timestamp / 1000, -// pos->x, -// pos->y, -// pos->z, -// pos->vx, -// pos->vy, -// pos->vz); +// pos.timestamp / 1000, +// pos.x, +// pos.y, +// pos.z, +// pos.vx, +// pos.vy, +// pos.vz); // } // } // }; @@ -716,13 +718,13 @@ protected: // { // if (pos_sub->update(t)) { // mavlink_msg_vicon_position_estimate_send(_channel, -// pos->timestamp / 1000, -// pos->x, -// pos->y, -// pos->z, -// pos->roll, -// pos->pitch, -// pos->yaw); +// pos.timestamp / 1000, +// pos.x, +// pos.y, +// pos.z, +// pos.roll, +// pos.pitch, +// pos.yaw); // } // } // }; @@ -1106,131 +1108,171 @@ protected: // }; -// class MavlinkStreamRCChannelsRaw : public MavlinkStream -// { -// public: -// const char *get_name() -// { -// return "RC_CHANNELS_RAW"; -// } +class MavlinkStreamRCChannelsRaw : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamRCChannelsRaw::get_name_static(); + } -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamRCChannelsRaw(); -// } + static const char *get_name_static() + { + return "RC_CHANNELS_RAW"; + } -// private: -// MavlinkOrbSubscription *rc_sub; -// struct rc_input_values *rc; + static MavlinkStream *new_instance() + { + return new MavlinkStreamRCChannelsRaw(); + } -// protected: -// void subscribe(Mavlink *mavlink) -// { -// rc_sub = mavlink->add_orb_subscription(ORB_ID(input_rc)); -// rc = (struct rc_input_values *)rc_sub->get_data(); -// } +private: + MavlinkOrbSubscription *rc_sub; -// void send(const hrt_abstime t) -// { -// if (rc_sub->update(t)) { -// const unsigned port_width = 8; - -// 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); -// } -// } -// } -// }; +protected: + 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(t, &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 > 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.channel_count, + rc.rssi); + } + } +}; -// class MavlinkStreamManualControl : public MavlinkStream -// { -// public: -// const char *get_name() -// { -// return "MANUAL_CONTROL"; -// } -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamManualControl(); -// } +class MavlinkStreamManualControl : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamManualControl::get_name_static(); + } -// private: -// MavlinkOrbSubscription *manual_sub; -// struct manual_control_setpoint_s *manual; + static const char *get_name_static() + { + return "MANUAL_CONTROL"; + } -// protected: -// void subscribe(Mavlink *mavlink) -// { -// manual_sub = mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); -// manual = (struct manual_control_setpoint_s *)manual_sub->get_data(); -// } + static MavlinkStream *new_instance() + { + return new MavlinkStreamManualControl(); + } -// void send(const hrt_abstime t) -// { -// if (manual_sub->update(t)) { -// mavlink_msg_manual_control_send(_channel, -// mavlink_system.sysid, -// manual->x * 1000, -// manual->y * 1000, -// manual->z * 1000, -// manual->r * 1000, -// 0); -// } -// } -// }; +private: + MavlinkOrbSubscription *manual_sub; +protected: + void subscribe(Mavlink *mavlink) + { + manual_sub = mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); + } -// class MavlinkStreamOpticalFlow : public MavlinkStream -// { -// public: -// const char *get_name() -// { -// return "OPTICAL_FLOW"; -// } + void send(const hrt_abstime t) + { + struct manual_control_setpoint_s manual; + + if (manual_sub->update(t, &manual)) { + mavlink_msg_manual_control_send(_channel, + mavlink_system.sysid, + manual.x * 1000, + manual.y * 1000, + manual.z * 1000, + manual.r * 1000, + 0); + } + } +}; -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamOpticalFlow(); -// } -// private: -// MavlinkOrbSubscription *flow_sub; -// struct optical_flow_s *flow; +class MavlinkStreamOpticalFlow : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamOpticalFlow::get_name_static(); + } -// protected: -// void subscribe(Mavlink *mavlink) -// { -// flow_sub = mavlink->add_orb_subscription(ORB_ID(optical_flow)); -// flow = (struct optical_flow_s *)flow_sub->get_data(); -// } + static const char *get_name_static() + { + return "OPTICAL_FLOW"; + } -// void send(const hrt_abstime t) -// { -// if (flow_sub->update(t)) { -// 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); -// } -// } -// }; + static MavlinkStream *new_instance() + { + return new MavlinkStreamOpticalFlow(); + } + +private: + MavlinkOrbSubscription *flow_sub; + +protected: + 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(t, &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 // { @@ -1413,7 +1455,7 @@ StreamListItem *streams_list[] = { 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 MavlinkStreamGlobalPositionInt(), + new StreamListItem(&MavlinkStreamGlobalPositionInt::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static), // new MavlinkStreamLocalPositionNED(), // new MavlinkStreamGPSGlobalOrigin(), // new MavlinkStreamServoOutputRaw(0), @@ -1425,9 +1467,9 @@ StreamListItem *streams_list[] = { // new MavlinkStreamLocalPositionSetpoint(), // new MavlinkStreamRollPitchYawThrustSetpoint(), // new MavlinkStreamRollPitchYawRatesThrustSetpoint(), - // new MavlinkStreamRCChannelsRaw(), - // new MavlinkStreamManualControl(), - // new MavlinkStreamOpticalFlow(), + new StreamListItem(&MavlinkStreamRCChannelsRaw::new_instance, &MavlinkStreamGlobalPositionInt::get_name_static), + new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static), + new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static), // new MavlinkStreamAttitudeControls(), // new MavlinkStreamNamedValueFloat(), // new MavlinkStreamCameraCapture(), -- cgit v1.2.3 From 9b2370e3873d65b65fd2dc2257beed50df6ac892 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 16 May 2014 17:10:11 +0200 Subject: mavlink app: Fix compile error --- src/modules/mavlink/mavlink_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 340b20e1b..e9932aac3 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1483,9 +1483,9 @@ void Mavlink::mavlink_wpm_message_handler(const mavlink_message_t *msg) void Mavlink::mavlink_missionlib_send_message(mavlink_message_t *msg) { - uint8_t missionlib_msg_buf[MAVLINK_MAX_PACKET_LEN]; + uint8_t buf[MAVLINK_MAX_PACKET_LEN]; - uint16_t len = mavlink_msg_to_send_buffer(missionlib_msg_buf, msg); + uint16_t len = mavlink_msg_to_send_buffer(buf, msg); mavlink_send_uart_bytes(_channel, buf, len); } -- cgit v1.2.3 From 7bfcaafc1631cab603191777e2e63f69755e334d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Fri, 16 May 2014 17:10:33 +0200 Subject: mavlink app: Finish porting all messages to new scheme --- src/modules/mavlink/mavlink_messages.cpp | 1362 ++++++++++++++++-------------- 1 file changed, 717 insertions(+), 645 deletions(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 3a82f1f05..748c1f69a 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -649,463 +649,514 @@ protected: }; -// class MavlinkStreamLocalPositionNED : public MavlinkStream -// { -// public: -// const char *get_name() -// { -// return "LOCAL_POSITION_NED"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamLocalPositionNED(); -// } - -// private: -// MavlinkOrbSubscription *pos_sub; -// struct vehicle_local_position_s *pos; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position)); -// pos = (struct vehicle_local_position_s *)pos_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (pos_sub->update(t)) { -// 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() -// { -// return "VICON_POSITION_ESTIMATE"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamViconPositionEstimate(); -// } - -// private: -// MavlinkOrbSubscription *pos_sub; -// struct vehicle_vicon_position_s *pos; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position)); -// pos = (struct vehicle_vicon_position_s *)pos_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (pos_sub->update(t)) { -// 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() -// { -// return "GPS_GLOBAL_ORIGIN"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamGPSGlobalOrigin(); -// } - -// private: -// MavlinkOrbSubscription *home_sub; -// struct home_position_s *home; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// home_sub = mavlink->add_orb_subscription(ORB_ID(home_position)); -// home = (struct home_position_s *)home_sub->get_data(); -// } - -// 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()) { -// home_sub->update(t); - -// mavlink_msg_gps_global_origin_send(_channel, -// (int32_t)(home->lat * 1e7), -// (int32_t)(home->lon * 1e7), -// (int32_t)(home->alt) * 1000.0f); -// } -// } -// }; - - -// class MavlinkStreamServoOutputRaw : public MavlinkStream -// { -// public: -// MavlinkStreamServoOutputRaw(unsigned int n) : MavlinkStream(), _n(n) -// { -// sprintf(_name, "SERVO_OUTPUT_RAW_%d", _n); -// } - -// const char *get_name() -// { -// return _name; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamServoOutputRaw(_n); -// } - -// private: -// MavlinkOrbSubscription *act_sub; -// struct actuator_outputs_s *act; - -// char _name[20]; -// unsigned int _n; - -// protected: -// 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]); -// act = (struct actuator_outputs_s *)act_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (act_sub->update(t)) { -// 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() -// { -// return "HIL_CONTROLS"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamHILControls(); -// } - -// private: -// MavlinkOrbSubscription *status_sub; -// struct vehicle_status_s *status; - -// MavlinkOrbSubscription *pos_sp_triplet_sub; -// struct position_setpoint_triplet_s *pos_sp_triplet; - -// MavlinkOrbSubscription *act_sub; -// struct actuator_outputs_s *act; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); -// status = (struct vehicle_status_s *)status_sub->get_data(); - -// pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); -// pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data(); - -// act_sub = mavlink->add_orb_subscription(ORB_ID(actuator_outputs_0)); -// act = (struct actuator_outputs_s *)act_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// bool updated = act_sub->update(t); -// (void)pos_sp_triplet_sub->update(t); -// (void)status_sub->update(t); - -// 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); - -// 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 */ -// unsigned n; - -// switch (mavlink_system.type) { -// case MAV_TYPE_QUADROTOR: -// n = 4; -// break; - -// case MAV_TYPE_HEXAROTOR: -// n = 6; -// break; - -// default: -// n = 8; -// 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 */ -// out[i] = (act->output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); - -// } else { -// /* send 0 when disarmed */ -// out[i] = 0.0f; -// } - -// } else { -// out[i] = -1.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; - -// for (unsigned i = 0; i < 8; i++) { -// if (i != 3) { -// /* scale fake 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 */ -// 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() -// { -// return "GLOBAL_POSITION_SETPOINT_INT"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamGlobalPositionSetpointInt(); -// } - -// private: -// MavlinkOrbSubscription *pos_sp_triplet_sub; -// struct position_setpoint_triplet_s *pos_sp_triplet; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); -// pos_sp_triplet = (struct position_setpoint_triplet_s *)pos_sp_triplet_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (pos_sp_triplet_sub->update(t)) { -// 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() -// { -// return "LOCAL_POSITION_SETPOINT"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamLocalPositionSetpoint(); -// } - -// private: -// MavlinkOrbSubscription *pos_sp_sub; -// struct vehicle_local_position_setpoint_s *pos_sp; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// pos_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint)); -// pos_sp = (struct vehicle_local_position_setpoint_s *)pos_sp_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (pos_sp_sub->update(t)) { -// 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() -// { -// return "ROLL_PITCH_YAW_THRUST_SETPOINT"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamRollPitchYawThrustSetpoint(); -// } - -// private: -// MavlinkOrbSubscription *att_sp_sub; -// struct vehicle_attitude_setpoint_s *att_sp; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// att_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint)); -// att_sp = (struct vehicle_attitude_setpoint_s *)att_sp_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (att_sp_sub->update(t)) { -// 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() -// { -// return "ROLL_PITCH_YAW_RATES_THRUST_SETPOINT"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamRollPitchYawRatesThrustSetpoint(); -// } - -// private: -// MavlinkOrbSubscription *att_rates_sp_sub; -// struct vehicle_rates_setpoint_s *att_rates_sp; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// att_rates_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint)); -// att_rates_sp = (struct vehicle_rates_setpoint_s *)att_rates_sp_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (att_rates_sp_sub->update(t)) { -// 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 MavlinkStreamLocalPositionNED : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamLocalPositionNED::get_name_static(); + } + + static const char *get_name_static() + { + return "LOCAL_POSITION_NED"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamLocalPositionNED(); + } + +private: + MavlinkOrbSubscription *pos_sub; + +protected: + 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(t, &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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamViconPositionEstimate(); + } + +private: + MavlinkOrbSubscription *pos_sub; + +protected: + 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(t, &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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamGPSGlobalOrigin(); + } + +private: + MavlinkOrbSubscription *home_sub; + +protected: + 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; + home_sub->update(t, &home); + + mavlink_msg_gps_global_origin_send(_channel, + (int32_t)(home.lat * 1e7), + (int32_t)(home.lon * 1e7), + (int32_t)(home.alt) * 1000.0f); + } + } +}; + + +class MavlinkStreamServoOutputRaw : public MavlinkStream +{ +public: + MavlinkStreamServoOutputRaw() : MavlinkStream() + { + _instance = _n++; + } + + const char *get_name() const + { + return get_name_static_int(_instance); + } + + static const char *get_name_static() + { + return get_name_static_int(_n); + } + + static const char *get_name_static_int(unsigned n) + { + 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(); + } + + static unsigned _n; + +private: + MavlinkOrbSubscription *_act_sub; + + unsigned _instance; + +protected: + 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[_instance]); + } + + void send(const hrt_abstime t) + { + struct actuator_outputs_s act; + + if (_act_sub->update(t, &act)) { + mavlink_msg_servo_output_raw_send(_channel, + act.timestamp / 1000, + _instance, + 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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamHILControls(); + } + +private: + MavlinkOrbSubscription *status_sub; + MavlinkOrbSubscription *pos_sp_triplet_sub; + MavlinkOrbSubscription *act_sub; + +protected: + 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(t, &act); + (void)pos_sp_triplet_sub->update(t, &pos_sp_triplet); + (void)status_sub->update(t, &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); + + 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 */ + unsigned n; + + switch (mavlink_system.type) { + case MAV_TYPE_QUADROTOR: + n = 4; + break; + + case MAV_TYPE_HEXAROTOR: + n = 6; + break; + + default: + n = 8; + 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 */ + out[i] = (act.output[i] - PWM_LOWEST_MIN) / (PWM_HIGHEST_MAX - PWM_LOWEST_MIN); + + } else { + /* send 0 when disarmed */ + out[i] = 0.0f; + } + + } else { + out[i] = -1.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; + + for (unsigned i = 0; i < 8; i++) { + if (i != 3) { + /* scale fake 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 */ + 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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamGlobalPositionSetpointInt(); + } + +private: + MavlinkOrbSubscription *pos_sp_triplet_sub; + +protected: + 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(t, &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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamLocalPositionSetpoint(); + } + +private: + MavlinkOrbSubscription *pos_sp_sub; + +protected: + 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(t, &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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamRollPitchYawThrustSetpoint(); + } + +private: + MavlinkOrbSubscription *att_sp_sub; + +protected: + 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(t, &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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamRollPitchYawRatesThrustSetpoint(); + } + +private: + MavlinkOrbSubscription *att_rates_sp_sub; + +protected: + 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(t, &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 @@ -1274,178 +1325,199 @@ protected: } }; -// class MavlinkStreamAttitudeControls : public MavlinkStream -// { -// public: -// const char *get_name() -// { -// return "ATTITUDE_CONTROLS"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamAttitudeControls(); -// } - -// private: -// MavlinkOrbSubscription *att_ctrl_sub; -// struct actuator_controls_s *att_ctrl; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// att_ctrl_sub = mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); -// att_ctrl = (struct actuator_controls_s *)att_ctrl_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (att_ctrl_sub->update(t)) { -// /* 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() -// { -// return "NAMED_VALUE_FLOAT"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamNamedValueFloat(); -// } - -// private: -// MavlinkOrbSubscription *debug_sub; -// struct debug_key_value_s *debug; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// debug_sub = mavlink->add_orb_subscription(ORB_ID(debug_key_value)); -// debug = (struct debug_key_value_s *)debug_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (debug_sub->update(t)) { -// /* 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() -// { -// return "CAMERA_CAPTURE"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamCameraCapture(); -// } - -// private: -// MavlinkOrbSubscription *status_sub; -// struct vehicle_status_s *status; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); -// status = (struct vehicle_status_s *)status_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// (void)status_sub->update(t); - -// 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() -// { -// return "DISTANCE_SENSOR"; -// } - -// MavlinkStream *new_instance() -// { -// return new MavlinkStreamDistanceSensor(); -// } - -// private: -// MavlinkOrbSubscription *range_sub; -// struct range_finder_report *range; - -// protected: -// void subscribe(Mavlink *mavlink) -// { -// range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder)); -// range = (struct range_finder_report *)range_sub->get_data(); -// } - -// void send(const hrt_abstime t) -// { -// if (range_sub->update(t)) { - -// 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 MavlinkStreamAttitudeControls : public MavlinkStream +{ +public: + const char *get_name() const + { + return MavlinkStreamAttitudeControls::get_name_static(); + } + + static const char *get_name_static() + { + return "ATTITUDE_CONTROLS"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamAttitudeControls(); + } + +private: + MavlinkOrbSubscription *att_ctrl_sub; + +protected: + 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(t, &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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamNamedValueFloat(); + } + +private: + MavlinkOrbSubscription *debug_sub; + +protected: + 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(t, &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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamCameraCapture(); + } + +private: + MavlinkOrbSubscription *status_sub; + +protected: + 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(t, &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"; + } + + static MavlinkStream *new_instance() + { + return new MavlinkStreamDistanceSensor(); + } + +private: + MavlinkOrbSubscription *range_sub; + +protected: + 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(t, &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); + } + } +}; + +unsigned MavlinkStreamServoOutputRaw::_n = 0; StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static), @@ -1456,24 +1528,24 @@ StreamListItem *streams_list[] = { 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 MavlinkStreamLocalPositionNED(), - // new MavlinkStreamGPSGlobalOrigin(), - // new MavlinkStreamServoOutputRaw(0), - // new MavlinkStreamServoOutputRaw(1), - // new MavlinkStreamServoOutputRaw(2), - // new MavlinkStreamServoOutputRaw(3), - // new MavlinkStreamHILControls(), - // new MavlinkStreamGlobalPositionSetpointInt(), - // new MavlinkStreamLocalPositionSetpoint(), - // new MavlinkStreamRollPitchYawThrustSetpoint(), - // new MavlinkStreamRollPitchYawRatesThrustSetpoint(), + new StreamListItem(&MavlinkStreamLocalPositionNED::new_instance, &MavlinkStreamLocalPositionNED::get_name_static), + new StreamListItem(&MavlinkStreamGPSGlobalOrigin::new_instance, &MavlinkStreamGPSGlobalOrigin::get_name_static), + new StreamListItem(&MavlinkStreamServoOutputRaw::new_instance, &MavlinkStreamServoOutputRaw::get_name_static), + new StreamListItem(&MavlinkStreamServoOutputRaw::new_instance, &MavlinkStreamServoOutputRaw::get_name_static), + new StreamListItem(&MavlinkStreamServoOutputRaw::new_instance, &MavlinkStreamServoOutputRaw::get_name_static), + new StreamListItem(&MavlinkStreamServoOutputRaw::new_instance, &MavlinkStreamServoOutputRaw::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, &MavlinkStreamGlobalPositionInt::get_name_static), new StreamListItem(&MavlinkStreamManualControl::new_instance, &MavlinkStreamManualControl::get_name_static), new StreamListItem(&MavlinkStreamOpticalFlow::new_instance, &MavlinkStreamOpticalFlow::get_name_static), - // new MavlinkStreamAttitudeControls(), - // new MavlinkStreamNamedValueFloat(), - // new MavlinkStreamCameraCapture(), - // new MavlinkStreamDistanceSensor(), - // new MavlinkStreamViconPositionEstimate(), + 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 }; -- cgit v1.2.3 From 342e08977ae5bf49c5ba941866e44fddefca4cda Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Wed, 11 Jun 2014 14:00:44 +0200 Subject: MavlinkOrbSubscription API reworked --- src/modules/mavlink/mavlink_commands.cpp | 8 +- src/modules/mavlink/mavlink_commands.h | 2 +- src/modules/mavlink/mavlink_main.cpp | 8 +- src/modules/mavlink/mavlink_messages.cpp | 311 +++++++++++++++-------- src/modules/mavlink/mavlink_orb_subscription.cpp | 38 ++- src/modules/mavlink/mavlink_orb_subscription.h | 18 +- 6 files changed, 248 insertions(+), 137 deletions(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_commands.cpp b/src/modules/mavlink/mavlink_commands.cpp index 5760d7512..fccd4d9a5 100644 --- a/src/modules/mavlink/mavlink_commands.cpp +++ b/src/modules/mavlink/mavlink_commands.cpp @@ -40,21 +40,17 @@ #include "mavlink_commands.h" -MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel) +MavlinkCommandsStream::MavlinkCommandsStream(Mavlink *mavlink, mavlink_channel_t channel) : _channel(channel), _cmd_time(0) { _cmd_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_command)); } -MavlinkCommandsStream::~MavlinkCommandsStream() -{ -} - void MavlinkCommandsStream::update(const hrt_abstime t) { struct vehicle_command_s cmd; - if (_cmd_sub->update(t, &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, diff --git a/src/modules/mavlink/mavlink_commands.h b/src/modules/mavlink/mavlink_commands.h index 6255d65df..abdba34b9 100644 --- a/src/modules/mavlink/mavlink_commands.h +++ b/src/modules/mavlink/mavlink_commands.h @@ -55,10 +55,10 @@ 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); - ~MavlinkCommandsStream(); void update(const hrt_abstime t); }; diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 39610fdd8..046f45bd9 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1900,10 +1900,12 @@ Mavlink::task_main(int argc, char *argv[]) _task_running = true; MavlinkOrbSubscription *param_sub = add_orb_subscription(ORB_ID(parameter_update)); + uint64_t param_time = 0; MavlinkOrbSubscription *status_sub = add_orb_subscription(ORB_ID(vehicle_status)); + uint64_t status_time = 0; struct vehicle_status_s status; - status_sub->update(0, &status); + status_sub->update(&status_time, &status); MavlinkCommandsStream commands_stream(this, _channel); @@ -1960,12 +1962,12 @@ Mavlink::task_main(int argc, char *argv[]) hrt_abstime t = hrt_absolute_time(); - if (param_sub->update(t, nullptr)) { + if (param_sub->update(¶m_time, nullptr)) { /* parameters updated */ mavlink_update_system(); } - if (status_sub->update(t, &status)) { + if (status_sub->update(&status_time, &status)) { /* switch HIL mode if required */ set_hil_enabled(status.hil_state == HIL_STATE_ON); } diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 184726fe8..0430987ec 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -195,9 +195,6 @@ void get_mavlink_mode_state(struct vehicle_status_s *status, struct position_set class MavlinkStreamHeartbeat : public MavlinkStream { public: - - ~MavlinkStreamHeartbeat() {}; - const char *get_name() const { return MavlinkStreamHeartbeat::get_name_static(); @@ -216,12 +213,8 @@ public: private: MavlinkOrbSubscription *status_sub; MavlinkOrbSubscription *pos_sp_triplet_sub; - protected: - - explicit MavlinkStreamHeartbeat() {}; - void subscribe(Mavlink *mavlink) { status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); @@ -233,21 +226,19 @@ protected: struct vehicle_status_s status; struct position_setpoint_triplet_s pos_sp_triplet; - (void)status_sub->update(t, &status); - (void)pos_sp_triplet_sub->update(t, &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); + if (status_sub->update(&status) && pos_sp_triplet_sub->update(&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); + } } }; @@ -255,8 +246,6 @@ protected: class MavlinkStreamSysStatus : public MavlinkStream { public: - ~MavlinkStreamSysStatus() {}; - const char *get_name() const { return MavlinkStreamSysStatus::get_name_static(); @@ -274,11 +263,8 @@ public: private: MavlinkOrbSubscription *status_sub; - struct vehicle_status_s *status; protected: - explicit MavlinkStreamSysStatus() {}; - void subscribe(Mavlink *mavlink) { status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); @@ -287,21 +273,23 @@ protected: void send(const hrt_abstime t) { struct vehicle_status_s status; - (void)status_sub->update(t, &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); + + 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); + } } }; @@ -309,8 +297,6 @@ protected: class MavlinkStreamHighresIMU : public MavlinkStream { public: - ~MavlinkStreamHighresIMU() {}; - const char *get_name() const { return MavlinkStreamHighresIMU::get_name_static(); @@ -328,6 +314,7 @@ public: private: MavlinkOrbSubscription *sensor_sub; + uint64_t sensor_time; uint64_t accel_timestamp; uint64_t gyro_timestamp; @@ -335,9 +322,13 @@ private: uint64_t baro_timestamp; protected: - explicit MavlinkStreamHighresIMU() : MavlinkStream(), accel_timestamp(0), gyro_timestamp(0), mag_timestamp(0), baro_timestamp(0) - { - } + explicit MavlinkStreamHighresIMU() : MavlinkStream(), + sensor_time(0), + accel_timestamp(0), + gyro_timestamp(0), + mag_timestamp(0), + baro_timestamp(0) + {} void subscribe(Mavlink *mavlink) { @@ -347,7 +338,8 @@ protected: void send(const hrt_abstime t) { struct sensor_combined_s sensor; - if (sensor_sub->update(t, &sensor)) { + + if (sensor_sub->update(&sensor_time, &sensor)) { uint16_t fields_updated = 0; if (accel_timestamp != sensor.accelerometer_timestamp) { @@ -407,9 +399,13 @@ public: private: MavlinkOrbSubscription *att_sub; - struct vehicle_attitude_s *att; + uint64_t att_time; protected: + explicit MavlinkStreamAttitude() : MavlinkStream(), + att_time(0) + {} + void subscribe(Mavlink *mavlink) { att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); @@ -419,7 +415,7 @@ protected: { struct vehicle_attitude_s att; - if (att_sub->update(t, &att)) { + if (att_sub->update(&att_time, &att)) { mavlink_msg_attitude_send(_channel, att.timestamp / 1000, att.roll, att.pitch, att.yaw, @@ -449,8 +445,13 @@ public: private: MavlinkOrbSubscription *att_sub; + uint64_t att_time; protected: + explicit MavlinkStreamAttitudeQuaternion() : MavlinkStream(), + att_time(0) + {} + void subscribe(Mavlink *mavlink) { att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); @@ -460,7 +461,7 @@ protected: { struct vehicle_attitude_s att; - if (att_sub->update(t, &att)) { + if (att_sub->update(&att_time, &att)) { mavlink_msg_attitude_quaternion_send(_channel, att.timestamp / 1000, att.q[0], @@ -496,21 +497,29 @@ public: private: MavlinkOrbSubscription *att_sub; - struct vehicle_attitude_s *att; + uint64_t att_time; MavlinkOrbSubscription *pos_sub; - struct vehicle_global_position_s *pos; + uint64_t pos_time; MavlinkOrbSubscription *armed_sub; - struct actuator_armed_s *armed; + uint64_t armed_time; MavlinkOrbSubscription *act_sub; - struct actuator_controls_s *act; + uint64_t act_time; MavlinkOrbSubscription *airspeed_sub; - struct airspeed_s *airspeed; + uint64_t airspeed_time; protected: + explicit MavlinkStreamVFRHUD() : MavlinkStream(), + att_time(0), + pos_time(0), + armed_time(0), + act_time(0), + airspeed_time(0) + {} + void subscribe(Mavlink *mavlink) { att_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude)); @@ -528,11 +537,11 @@ protected: struct actuator_controls_s act; struct airspeed_s airspeed; - bool updated = att_sub->update(t, &att); - updated |= pos_sub->update(t, &pos); - updated |= armed_sub->update(t, &armed); - updated |= act_sub->update(t, &act); - updated |= airspeed_sub->update(t, &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); @@ -571,9 +580,13 @@ public: private: MavlinkOrbSubscription *gps_sub; - struct vehicle_gps_position_s *gps; + uint64_t gps_time; protected: + explicit MavlinkStreamGPSRawInt() : MavlinkStream(), + gps_time(0) + {} + void subscribe(Mavlink *mavlink) { gps_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_gps_position)); @@ -583,7 +596,7 @@ protected: { struct vehicle_gps_position_s gps; - if (gps_sub->update(t, &gps)) { + if (gps_sub->update(&gps_time, &gps)) { mavlink_msg_gps_raw_int_send(_channel, gps.timestamp_position, gps.fix_type, @@ -620,9 +633,17 @@ public: private: MavlinkOrbSubscription *pos_sub; + uint64_t pos_time; + MavlinkOrbSubscription *home_sub; + uint64_t home_time; protected: + explicit MavlinkStreamGlobalPositionInt() : MavlinkStream(), + pos_time(0), + home_time(0) + {} + void subscribe(Mavlink *mavlink) { pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_global_position)); @@ -634,8 +655,8 @@ protected: struct vehicle_global_position_s pos; struct home_position_s home; - bool updated = pos_sub->update(t, &pos); - updated |= home_sub->update(t, &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, @@ -673,8 +694,13 @@ public: private: MavlinkOrbSubscription *pos_sub; + uint64_t pos_time; protected: + explicit MavlinkStreamLocalPositionNED() : MavlinkStream(), + pos_time(0) + {} + void subscribe(Mavlink *mavlink) { pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position)); @@ -684,7 +710,7 @@ protected: { struct vehicle_local_position_s pos; - if (pos_sub->update(t, &pos)) { + if (pos_sub->update(&pos_time, &pos)) { mavlink_msg_local_position_ned_send(_channel, pos.timestamp / 1000, pos.x, @@ -719,8 +745,13 @@ public: private: MavlinkOrbSubscription *pos_sub; + uint64_t pos_time; protected: + explicit MavlinkStreamViconPositionEstimate() : MavlinkStream(), + pos_time(0) + {} + void subscribe(Mavlink *mavlink) { pos_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_vicon_position)); @@ -730,7 +761,7 @@ protected: { struct vehicle_vicon_position_s pos; - if (pos_sub->update(t, &pos)) { + if (pos_sub->update(&pos_time, &pos)) { mavlink_msg_vicon_position_estimate_send(_channel, pos.timestamp / 1000, pos.x, @@ -777,38 +808,29 @@ protected: * the GCS does pick it up at one point */ if (home_sub->is_published()) { struct home_position_s home; - home_sub->update(t, &home); - mavlink_msg_gps_global_origin_send(_channel, - (int32_t)(home.lat * 1e7), - (int32_t)(home.lon * 1e7), - (int32_t)(home.alt) * 1000.0f); + 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: - MavlinkStreamServoOutputRaw() : MavlinkStream() - { - _instance = _n++; - } - const char *get_name() const { - return get_name_static_int(_instance); + return MavlinkStreamServoOutputRaw::get_name_static(); } static const char *get_name_static() { - return get_name_static_int(_n); - } - - static const char *get_name_static_int(unsigned n) - { - switch (n) { + switch (N) { case 0: return "SERVO_OUTPUT_RAW_0"; @@ -825,17 +847,18 @@ public: static MavlinkStream *new_instance() { - return new MavlinkStreamServoOutputRaw(); + return new MavlinkStreamServoOutputRaw(); } - static unsigned _n; - private: - MavlinkOrbSubscription *_act_sub; - - unsigned _instance; + MavlinkOrbSubscription *act_sub; + uint64_t act_time; protected: + explicit MavlinkStreamServoOutputRaw() : MavlinkStream(), + act_time(0) + {} + void subscribe(Mavlink *mavlink) { orb_id_t act_topics[] = { @@ -845,17 +868,17 @@ protected: ORB_ID(actuator_outputs_3) }; - _act_sub = mavlink->add_orb_subscription(act_topics[_instance]); + act_sub = mavlink->add_orb_subscription(act_topics[N]); } void send(const hrt_abstime t) { struct actuator_outputs_s act; - if (_act_sub->update(t, &act)) { + if (act_sub->update(&act_time, &act)) { mavlink_msg_servo_output_raw_send(_channel, act.timestamp / 1000, - _instance, + N, act.output[0], act.output[1], act.output[2], @@ -889,10 +912,21 @@ public: 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; protected: + explicit MavlinkStreamHILControls() : MavlinkStream(), + status_time(0), + pos_sp_triplet_time(0), + act_time(0) + {} + void subscribe(Mavlink *mavlink) { status_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_status)); @@ -906,9 +940,9 @@ protected: struct position_setpoint_triplet_s pos_sp_triplet; struct actuator_outputs_s act; - bool updated = act_sub->update(t, &act); - (void)pos_sp_triplet_sub->update(t, &pos_sp_triplet); - (void)status_sub->update(t, &status); + 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 */ @@ -1015,8 +1049,13 @@ public: private: MavlinkOrbSubscription *pos_sp_triplet_sub; + uint64_t pos_sp_triplet_time; protected: + explicit MavlinkStreamGlobalPositionSetpointInt() : MavlinkStream(), + pos_sp_triplet_time(0) + {} + void subscribe(Mavlink *mavlink) { pos_sp_triplet_sub = mavlink->add_orb_subscription(ORB_ID(position_setpoint_triplet)); @@ -1025,7 +1064,8 @@ protected: void send(const hrt_abstime t) { struct position_setpoint_triplet_s pos_sp_triplet; - if (pos_sp_triplet_sub->update(t, &pos_sp_triplet)) { + + if (pos_sp_triplet_sub->update(&pos_sp_triplet_time, &pos_sp_triplet)) { mavlink_msg_global_position_setpoint_int_send(_channel, MAV_FRAME_GLOBAL, (int32_t)(pos_sp_triplet.current.lat * 1e7), @@ -1057,8 +1097,13 @@ public: private: MavlinkOrbSubscription *pos_sp_sub; + uint64_t pos_sp_time; protected: + explicit MavlinkStreamLocalPositionSetpoint() : MavlinkStream(), + pos_sp_time(0) + {} + void subscribe(Mavlink *mavlink) { pos_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_local_position_setpoint)); @@ -1067,7 +1112,8 @@ protected: void send(const hrt_abstime t) { struct vehicle_local_position_setpoint_s pos_sp; - if (pos_sp_sub->update(t, &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, @@ -1099,8 +1145,13 @@ public: private: MavlinkOrbSubscription *att_sp_sub; + uint64_t att_sp_time; protected: + explicit MavlinkStreamRollPitchYawThrustSetpoint() : MavlinkStream(), + att_sp_time(0) + {} + void subscribe(Mavlink *mavlink) { att_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_attitude_setpoint)); @@ -1109,7 +1160,8 @@ protected: void send(const hrt_abstime t) { struct vehicle_attitude_setpoint_s att_sp; - if (att_sp_sub->update(t, &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, @@ -1141,8 +1193,13 @@ public: private: MavlinkOrbSubscription *att_rates_sp_sub; + uint64_t att_rates_sp_time; protected: + explicit MavlinkStreamRollPitchYawRatesThrustSetpoint() : MavlinkStream(), + att_rates_sp_time(0) + {} + void subscribe(Mavlink *mavlink) { att_rates_sp_sub = mavlink->add_orb_subscription(ORB_ID(vehicle_rates_setpoint)); @@ -1151,7 +1208,8 @@ protected: void send(const hrt_abstime t) { struct vehicle_rates_setpoint_s att_rates_sp; - if (att_rates_sp_sub->update(t, &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, @@ -1183,8 +1241,13 @@ public: private: MavlinkOrbSubscription *rc_sub; + uint64_t rc_time; protected: + explicit MavlinkStreamRCChannelsRaw() : MavlinkStream(), + rc_time(0) + {} + void subscribe(Mavlink *mavlink) { rc_sub = mavlink->add_orb_subscription(ORB_ID(input_rc)); @@ -1194,7 +1257,7 @@ protected: { struct rc_input_values rc; - if (rc_sub->update(t, &rc)) { + if (rc_sub->update(&rc_time, &rc)) { const unsigned port_width = 8; // Deprecated message (but still needed for compatibility!) @@ -1262,8 +1325,13 @@ public: private: MavlinkOrbSubscription *manual_sub; + uint64_t manual_time; protected: + explicit MavlinkStreamManualControl() : MavlinkStream(), + manual_time(0) + {} + void subscribe(Mavlink *mavlink) { manual_sub = mavlink->add_orb_subscription(ORB_ID(manual_control_setpoint)); @@ -1273,7 +1341,7 @@ protected: { struct manual_control_setpoint_s manual; - if (manual_sub->update(t, &manual)) { + if (manual_sub->update(&manual_time, &manual)) { mavlink_msg_manual_control_send(_channel, mavlink_system.sysid, manual.x * 1000, @@ -1306,8 +1374,13 @@ public: private: MavlinkOrbSubscription *flow_sub; + uint64_t flow_time; protected: + explicit MavlinkStreamOpticalFlow() : MavlinkStream(), + flow_time(0) + {} + void subscribe(Mavlink *mavlink) { flow_sub = mavlink->add_orb_subscription(ORB_ID(optical_flow)); @@ -1317,7 +1390,7 @@ protected: { struct optical_flow_s flow; - if (flow_sub->update(t, &flow)) { + if (flow_sub->update(&flow_time, &flow)) { mavlink_msg_optical_flow_send(_channel, flow.timestamp, flow.sensor_id, @@ -1349,8 +1422,13 @@ public: private: MavlinkOrbSubscription *att_ctrl_sub; + uint64_t att_ctrl_time; protected: + explicit MavlinkStreamAttitudeControls() : MavlinkStream(), + att_ctrl_time(0) + {} + void subscribe(Mavlink *mavlink) { att_ctrl_sub = mavlink->add_orb_subscription(ORB_ID_VEHICLE_ATTITUDE_CONTROLS); @@ -1360,7 +1438,7 @@ protected: { struct actuator_controls_s att_ctrl; - if (att_ctrl_sub->update(t, &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, @@ -1402,8 +1480,13 @@ public: private: MavlinkOrbSubscription *debug_sub; + uint64_t debug_time; protected: + explicit MavlinkStreamNamedValueFloat() : MavlinkStream(), + debug_time(0) + {} + void subscribe(Mavlink *mavlink) { debug_sub = mavlink->add_orb_subscription(ORB_ID(debug_key_value)); @@ -1413,7 +1496,7 @@ protected: { struct debug_key_value_s debug; - if (debug_sub->update(t, &debug)) { + if (debug_sub->update(&debug_time, &debug)) { /* enforce null termination */ debug.key[sizeof(debug.key) - 1] = '\0'; @@ -1455,7 +1538,7 @@ protected: void send(const hrt_abstime t) { struct vehicle_status_s status; - (void)status_sub->update(t, &status); + (void)status_sub->update(&status); if (status.arming_state == ARMING_STATE_ARMED || status.arming_state == ARMING_STATE_ARMED_ERROR) { @@ -1490,8 +1573,13 @@ public: private: MavlinkOrbSubscription *range_sub; + uint64_t range_time; protected: + explicit MavlinkStreamDistanceSensor() : MavlinkStream(), + range_time(0) + {} + void subscribe(Mavlink *mavlink) { range_sub = mavlink->add_orb_subscription(ORB_ID(sensor_range_finder)); @@ -1501,7 +1589,7 @@ protected: { struct range_finder_report range; - if (range_sub->update(t, &range)) { + if (range_sub->update(&range_time, &range)) { uint8_t type; @@ -1521,7 +1609,6 @@ protected: } }; -unsigned MavlinkStreamServoOutputRaw::_n = 0; StreamListItem *streams_list[] = { new StreamListItem(&MavlinkStreamHeartbeat::new_instance, &MavlinkStreamHeartbeat::get_name_static), @@ -1534,10 +1621,10 @@ StreamListItem *streams_list[] = { 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::new_instance, &MavlinkStreamServoOutputRaw::get_name_static), - new StreamListItem(&MavlinkStreamServoOutputRaw::new_instance, &MavlinkStreamServoOutputRaw::get_name_static), - new StreamListItem(&MavlinkStreamServoOutputRaw::new_instance, &MavlinkStreamServoOutputRaw::get_name_static), - new StreamListItem(&MavlinkStreamServoOutputRaw::new_instance, &MavlinkStreamServoOutputRaw::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), diff --git a/src/modules/mavlink/mavlink_orb_subscription.cpp b/src/modules/mavlink/mavlink_orb_subscription.cpp index 0a23fb01e..901fa8f05 100644 --- a/src/modules/mavlink/mavlink_orb_subscription.cpp +++ b/src/modules/mavlink/mavlink_orb_subscription.cpp @@ -50,7 +50,6 @@ MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic) : _fd(orb_subscribe(_topic)), _published(false), _topic(topic), - _last_check(0), next(nullptr) { } @@ -67,24 +66,39 @@ MavlinkOrbSubscription::get_topic() const } bool -MavlinkOrbSubscription::update(const hrt_abstime t, void* data) +MavlinkOrbSubscription::update(uint64_t *time, void* data) { - if (_last_check == t) { - /* already checked right now, return result of the check */ - return _updated; + // TODO this is NOT atomic operation, we can get data newer than time + // if topic was published between orb_stat and orb_copy calls. - } else { - _last_check = t; - orb_check(_fd, &_updated); + uint64_t time_topic; + if (orb_stat(_fd, &time_topic)) { + /* error getting last topic publication time */ + time_topic = 0; + } + + if (orb_copy(_topic, _fd, data)) { + /* error copying topic data */ + memset(data, 0, _topic->o_size); + return false; - if (_updated && data) { - orb_copy(_topic, _fd, data); - _published = true; + } else { + /* data copied successfully */ + _published = true; + if (time_topic != *time) { + *time = time_topic; return true; + + } else { + return false; } } +} - return false; +bool +MavlinkOrbSubscription::update(void* data) +{ + return !orb_copy(_topic, _fd, data); } bool diff --git a/src/modules/mavlink/mavlink_orb_subscription.h b/src/modules/mavlink/mavlink_orb_subscription.h index abd4031bd..71efb43af 100644 --- a/src/modules/mavlink/mavlink_orb_subscription.h +++ b/src/modules/mavlink/mavlink_orb_subscription.h @@ -53,7 +53,21 @@ public: MavlinkOrbSubscription(const orb_id_t topic); ~MavlinkOrbSubscription(); - bool update(const hrt_abstime t, void* data); + /** + * Check if subscription updated and get data. + * + * @return true only if topic was updated and data copied to buffer successfully. + * If topic was not updated since last check it will return false but still copy the data. + * If no data available data buffer will be filled with zeroes. + */ + bool update(uint64_t *time, void* data); + + /** + * Copy topic data to given buffer. + * + * @return true only if topic data copied successfully. + */ + bool update(void* data); /** * Check if the topic has been published. @@ -68,8 +82,6 @@ private: const orb_id_t _topic; ///< topic metadata int _fd; ///< subscription handle bool _published; ///< topic was ever published - hrt_abstime _last_check; ///< time of last check - bool _updated; ///< updated on last check }; -- cgit v1.2.3 From 44481e3773b7a576b31727c64931216112d953e0 Mon Sep 17 00:00:00 2001 From: Anton Babushkin Date: Thu, 12 Jun 2014 12:01:54 +0200 Subject: mavlink: sign of climb rate fixed in VFR_HUD message --- src/modules/mavlink/mavlink_messages.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index e0a148b53..aff1aa929 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -554,7 +554,7 @@ protected: heading, throttle, pos.alt, - pos.vel_d); + -pos.vel_d); } } }; -- cgit v1.2.3 From 6d8dfd78f11fdff038f7f7504c507d25429db195 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sat, 14 Jun 2014 15:54:24 +0200 Subject: sdlog2/mtecs: fix length of field name --- src/modules/sdlog2/sdlog2_messages.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src/modules') diff --git a/src/modules/sdlog2/sdlog2_messages.h b/src/modules/sdlog2/sdlog2_messages.h index c42ff0afe..5645ebcf1 100644 --- a/src/modules/sdlog2/sdlog2_messages.h +++ b/src/modules/sdlog2/sdlog2_messages.h @@ -431,7 +431,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, "fffffffffffffB", "AltSP,Alt,FpaSP,Fpa,AsSP,As,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,Mod"), + LOG_FORMAT(TECS, "fffffffffffffB", "AltSP,Alt,FpaSP,Fpa,AsSP,As,AsF,AsDSP,AsD,TERSP,TER,EDRSP,EDR,M"), LOG_FORMAT(WIND, "ffff", "X,Y,CovX,CovY"), /* system-level messages, ID >= 0x80 */ -- cgit v1.2.3 From cfdbf2c5e914c6264d9158470d4f98c84a483f68 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Mon, 23 Jun 2014 11:15:27 +0200 Subject: perfcounter: write time unit for all fields --- src/modules/systemlib/perf_counter.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) (limited to 'src/modules') diff --git a/src/modules/systemlib/perf_counter.c b/src/modules/systemlib/perf_counter.c index 22182e39e..d6d8284d2 100644 --- a/src/modules/systemlib/perf_counter.c +++ b/src/modules/systemlib/perf_counter.c @@ -301,7 +301,7 @@ perf_print_counter_fd(int fd, perf_counter_t handle) case PC_ELAPSED: { struct perf_ctr_elapsed *pce = (struct perf_ctr_elapsed *)handle; - dprintf(fd, "%s: %llu events, %lluus elapsed, %llu avg, min %lluus max %lluus\n", + dprintf(fd, "%s: %llu events, %lluus elapsed, %lluus avg, min %lluus max %lluus\n", handle->name, pce->event_count, pce->time_total, @@ -314,7 +314,7 @@ perf_print_counter_fd(int fd, perf_counter_t handle) case PC_INTERVAL: { struct perf_ctr_interval *pci = (struct perf_ctr_interval *)handle; - dprintf(fd, "%s: %llu events, %llu avg, min %lluus max %lluus\n", + dprintf(fd, "%s: %llu events, %lluus avg, min %lluus max %lluus\n", handle->name, pci->event_count, (pci->time_last - pci->time_first) / pci->event_count, -- cgit v1.2.3 From 87857cdd48d43a28c3b8ed1f1fe500ad28a93bbc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 23 Jun 2014 13:45:20 +0200 Subject: Hotfix: Fix message name typo --- src/modules/mavlink/mavlink_messages.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index aff1aa929..fed2dfb0d 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1625,7 +1625,7 @@ StreamListItem *streams_list[] = { 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, &MavlinkStreamGlobalPositionInt::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), -- cgit v1.2.3 From a9653fa10db3884d3d17ee33f80f23aa2e3ef842 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 23 Jun 2014 13:51:05 +0200 Subject: Hotfix: Only orb_copy items in mavlink app if the timestamp changed --- src/modules/mavlink/mavlink_orb_subscription.cpp | 26 ++++++++++++++---------- 1 file changed, 15 insertions(+), 11 deletions(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_orb_subscription.cpp b/src/modules/mavlink/mavlink_orb_subscription.cpp index 901fa8f05..3807323c2 100644 --- a/src/modules/mavlink/mavlink_orb_subscription.cpp +++ b/src/modules/mavlink/mavlink_orb_subscription.cpp @@ -44,6 +44,8 @@ #include #include +#include + #include "mavlink_orb_subscription.h" MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic) : @@ -77,21 +79,23 @@ MavlinkOrbSubscription::update(uint64_t *time, void* data) time_topic = 0; } - if (orb_copy(_topic, _fd, data)) { - /* error copying topic data */ - memset(data, 0, _topic->o_size); - return false; + if (time_topic != *time) { - } else { - /* data copied successfully */ - _published = true; - if (time_topic != *time) { - *time = time_topic; - return true; + if (orb_copy(_topic, _fd, data)) { + /* error copying topic data */ + memset(data, 0, _topic->o_size); + //warnx("err copy, fd: %d, obj: %s, size: %d", _fd, _topic->o_name, _topic->o_size); + return false; } else { - return false; + /* data copied successfully */ + _published = true; + *time = time_topic; + return true; } + + } else { + return false; } } -- cgit v1.2.3 From bf5061aa21872c98576d46aee894e670ce0c52a0 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 23 Jun 2014 13:52:09 +0200 Subject: Fix error reporting in stream config, report if a stream was not found at all in stream list and return error --- src/modules/mavlink/mavlink_main.cpp | 36 ++++++++++++++++++++---------------- 1 file changed, 20 insertions(+), 16 deletions(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 046f45bd9..a9b8323f3 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1555,32 +1555,36 @@ Mavlink::configure_stream(const char *stream_name, const float rate) /* delete stream */ LL_DELETE(_streams, stream); delete stream; + warnx("deleted stream %s", stream->get_name()); } return OK; } } - if (interval > 0) { - /* search for stream with specified name in supported streams list */ - for (unsigned int i = 0; streams_list[i] != nullptr; i++) { + if (interval == 0) { + /* stream was not active and is requested to be disabled, do nothing */ + return OK; + } - 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->set_interval(interval); - stream->subscribe(this); - LL_APPEND(_streams, stream); - return OK; - } - } + /* search for stream with specified name in supported streams list */ + for (unsigned int i = 0; streams_list[i] != nullptr; i++) { - } else { - /* stream not found, nothing to disable */ - return OK; + 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->set_interval(interval); + stream->subscribe(this); + LL_APPEND(_streams, stream); + + return OK; + } } + /* if we reach here, the stream list does not contain the stream */ + warnx("stream %s not found", stream_name); + return ERROR; } -- cgit v1.2.3 From 68442e31ac6970be91592282c9b70ebc76fa142d Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 23 Jun 2014 14:56:48 +0200 Subject: Hotfix: Move channel count to right position --- src/modules/mavlink/mavlink_messages.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index fed2dfb0d..4433377c6 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -1275,6 +1275,7 @@ protected: // 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), @@ -1293,7 +1294,6 @@ protected: ((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.channel_count, rc.rssi); } } -- cgit v1.2.3 From 52d539d3cdf56eb4145dbf29c407bb0a1a7eebe5 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 24 Jun 2014 17:39:48 +0200 Subject: extend integrator reset flags in uorb attitude setpoint topic to all axes --- src/modules/uORB/topics/vehicle_attitude_setpoint.h | 2 ++ 1 file changed, 2 insertions(+) (limited to 'src/modules') diff --git a/src/modules/uORB/topics/vehicle_attitude_setpoint.h b/src/modules/uORB/topics/vehicle_attitude_setpoint.h index d526a8ff2..8446e9c6e 100644 --- a/src/modules/uORB/topics/vehicle_attitude_setpoint.h +++ b/src/modules/uORB/topics/vehicle_attitude_setpoint.h @@ -72,6 +72,8 @@ struct vehicle_attitude_setpoint_s { float thrust; /**< Thrust in Newton the power system should generate */ bool roll_reset_integral; /**< Reset roll integral part (navigation logic change) */ + bool pitch_reset_integral; /**< Reset pitch integral part (navigation logic change) */ + bool yaw_reset_integral; /**< Reset yaw integral part (navigation logic change) */ }; -- cgit v1.2.3 From 9a911f7388e1a48630469fd2e875f00a119c829a Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 24 Jun 2014 17:40:56 +0200 Subject: fw att control: reset integrators when requested via attitude setpoint topic --- src/modules/fw_att_control/fw_att_control_main.cpp | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) (limited to 'src/modules') 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..3cd4ce928 100644 --- a/src/modules/fw_att_control/fw_att_control_main.cpp +++ b/src/modules/fw_att_control/fw_att_control_main.cpp @@ -707,14 +707,21 @@ FixedwingAttitudeControl::task_main() float throttle_sp = 0.0f; if (_vcontrol_mode.flag_control_velocity_enabled || _vcontrol_mode.flag_control_position_enabled) { + /* read in attitude setpoint from attitude setpoint uorb topic */ roll_sp = _att_sp.roll_body + _parameters.rollsp_offset_rad; pitch_sp = _att_sp.pitch_body + _parameters.pitchsp_offset_rad; throttle_sp = _att_sp.thrust; /* reset integrals where needed */ - if (_att_sp.roll_reset_integral) + if (_att_sp.roll_reset_integral) { _roll_ctrl.reset_integrator(); - + } + if (_att_sp.pitch_reset_integral) { + _pitch_ctrl.reset_integrator(); + } + if (_att_sp.yaw_reset_integral) { + _yaw_ctrl.reset_integrator(); + } } else { /* * Scale down roll and pitch as the setpoints are radians -- cgit v1.2.3 From c6cdcfc2638f8d994b3716d8739614c5377c4962 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 24 Jun 2014 17:42:21 +0200 Subject: fw pos control: set integrator reset flags in attitude setpoint topic, set them to true when launchdetection is running (while waiting for launch) --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) (limited to 'src/modules') 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 116d3cc63..518116fa1 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 @@ -841,6 +841,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi /* current waypoint (the one currently heading for) */ math::Vector<2> curr_wp((float)pos_sp_triplet.current.lat, (float)pos_sp_triplet.current.lon); + /* Initialize attitude controller integrator reset flags to 0 */ + _att_sp.roll_reset_integral = false; + _att_sp.pitch_reset_integral = false; + _att_sp.yaw_reset_integral = false; /* previous waypoint */ math::Vector<2> prev_wp; @@ -1028,6 +1032,11 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi // warnx("Launch detection running"); mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running"); last_sent = hrt_absolute_time(); + /* Tell the attitude controller to stop integrating while we are + * waiting for the launch */ + _att_sp.roll_reset_integral = true; + _att_sp.pitch_reset_integral = true; + _att_sp.yaw_reset_integral = true; } launchDetector.update(_sensor_combined.accelerometer_m_s2[0]); if (launchDetector.getLaunchDetected()) { -- cgit v1.2.3 From 819812e11271d7b78f4af2d5bbb7ac6e4be9e494 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 24 Jun 2014 20:52:24 +0200 Subject: fw pos ctrl: move setting of attitude integral reset flag --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) (limited to 'src/modules') 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 518116fa1..fe5847682 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 @@ -1032,12 +1032,15 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi // warnx("Launch detection running"); mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running"); last_sent = hrt_absolute_time(); - /* Tell the attitude controller to stop integrating while we are - * waiting for the launch */ - _att_sp.roll_reset_integral = true; - _att_sp.pitch_reset_integral = true; - _att_sp.yaw_reset_integral = true; } + + /* Tell the attitude controller to stop integrating while we are waiting + * for the launch */ + _att_sp.roll_reset_integral = true; + _att_sp.pitch_reset_integral = true; + _att_sp.yaw_reset_integral = true; + + /* Detect launch */ launchDetector.update(_sensor_combined.accelerometer_m_s2[0]); if (launchDetector.getLaunchDetected()) { launch_detected = true; -- cgit v1.2.3 From 4f560f729ec1f40427401119a0f17d9d0e9843f4 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Tue, 24 Jun 2014 20:53:06 +0200 Subject: fw pos ctrl: remove comments --- src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp | 2 -- 1 file changed, 2 deletions(-) (limited to 'src/modules') 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 fe5847682..0e065211e 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 @@ -1024,12 +1024,10 @@ FixedwingPositionControl::control_position(const math::Vector<2> ¤t_positi } else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF) { /* Perform launch detection */ -// warnx("Launch detection running"); if(!launch_detected) { //do not do further checks once a launch was detected if (launchDetector.launchDetectionEnabled()) { static hrt_abstime last_sent = 0; if(hrt_absolute_time() - last_sent > 4e6) { -// warnx("Launch detection running"); mavlink_log_info(_mavlink_fd, "#audio: Launchdetection running"); last_sent = hrt_absolute_time(); } -- cgit v1.2.3 From f9d5cf332c9e60661c2e1c0827c84480e49d4fe8 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Wed, 25 Jun 2014 17:05:20 +0200 Subject: Revert "Hotfix: Only orb_copy items in mavlink app if the timestamp changed" This reverts commit a9653fa10db3884d3d17ee33f80f23aa2e3ef842. --- src/modules/mavlink/mavlink_orb_subscription.cpp | 26 ++++++++++-------------- 1 file changed, 11 insertions(+), 15 deletions(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_orb_subscription.cpp b/src/modules/mavlink/mavlink_orb_subscription.cpp index 3807323c2..901fa8f05 100644 --- a/src/modules/mavlink/mavlink_orb_subscription.cpp +++ b/src/modules/mavlink/mavlink_orb_subscription.cpp @@ -44,8 +44,6 @@ #include #include -#include - #include "mavlink_orb_subscription.h" MavlinkOrbSubscription::MavlinkOrbSubscription(const orb_id_t topic) : @@ -79,23 +77,21 @@ MavlinkOrbSubscription::update(uint64_t *time, void* data) time_topic = 0; } - if (time_topic != *time) { - - if (orb_copy(_topic, _fd, data)) { - /* error copying topic data */ - memset(data, 0, _topic->o_size); - //warnx("err copy, fd: %d, obj: %s, size: %d", _fd, _topic->o_name, _topic->o_size); - return false; + if (orb_copy(_topic, _fd, data)) { + /* error copying topic data */ + memset(data, 0, _topic->o_size); + return false; - } else { - /* data copied successfully */ - _published = true; + } else { + /* data copied successfully */ + _published = true; + if (time_topic != *time) { *time = time_topic; return true; - } - } else { - return false; + } else { + return false; + } } } -- cgit v1.2.3 From 831a3d4ed14bc068ee086c5190af96ad809f67d7 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 26 Jun 2014 07:47:46 +0200 Subject: mtecs: improve logic readability --- src/modules/fw_pos_control_l1/mtecs/mTecs.cpp | 11 +++-------- 1 file changed, 3 insertions(+), 8 deletions(-) (limited to 'src/modules') diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp index 03353cbc1..48c9079a4 100644 --- a/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp +++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.cpp @@ -199,8 +199,8 @@ int mTecs::updateFlightPathAngleAcceleration(float flightPathAngle, float flight } /* Set special ouput limiters if we are not in TECS_MODE_NORMAL */ - BlockOutputLimiter *outputLimiterThrottle = NULL; // NULL --> use standard inflight limits - BlockOutputLimiter *outputLimiterPitch = NULL; // NULL --> use standard inflight limits + BlockOutputLimiter *outputLimiterThrottle = &_controlTotalEnergy.getOutputLimiter(); + BlockOutputLimiter *outputLimiterPitch = &_controlEnergyDistribution.getOutputLimiter(); if (mode == TECS_MODE_TAKEOFF) { outputLimiterThrottle = &_BlockOutputLimiterTakeoffThrottle; //XXX: accept prelaunch values from launchdetector outputLimiterPitch = &_BlockOutputLimiterTakeoffPitch; @@ -218,12 +218,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 == NULL ? - _controlTotalEnergy.getOutputLimiter() : - *outputLimiterThrottle, - outputLimiterPitch == NULL ? - _controlEnergyDistribution.getOutputLimiter() : - *outputLimiterPitch); + bool limitApplied = limitOverride.applyOverride(*outputLimiterThrottle, *outputLimiterPitch); /* Write part of the status message */ _status.airspeedDerivativeSp = airspeedDerivativeSp; -- cgit v1.2.3 From 43c3559763841abacf5e74e15a6172026071088b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 26 Jun 2014 12:08:25 +0200 Subject: commander: Make mavlink_fd in arming command non-optional --- src/modules/commander/state_machine_helper.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'src/modules') diff --git a/src/modules/commander/state_machine_helper.h b/src/modules/commander/state_machine_helper.h index 0ddd4f05a..abb917873 100644 --- a/src/modules/commander/state_machine_helper.h +++ b/src/modules/commander/state_machine_helper.h @@ -57,7 +57,7 @@ typedef enum { } transition_result_t; 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 = 0); + arming_state_t new_arming_state, struct actuator_armed_s *armed, const int mavlink_fd); bool is_safe(const struct vehicle_status_s *current_state, const struct safety_s *safety, const struct actuator_armed_s *armed); -- cgit v1.2.3 From 547f71d791d0a04001580e8371bdf59b808a3d29 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 26 Jun 2014 12:07:28 +0200 Subject: Add mavlink_fd to all commander arm transitions to provide user feedback why the arming command failed --- src/modules/commander/commander.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) (limited to 'src/modules') diff --git a/src/modules/commander/commander.cpp b/src/modules/commander/commander.cpp index 65922b2a5..588f48225 100644 --- a/src/modules/commander/commander.cpp +++ b/src/modules/commander/commander.cpp @@ -412,7 +412,7 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe /* if HIL got enabled, reset battery status state */ if (hil_ret == OK && status->hil_state == HIL_STATE_ON) { /* reset the arming mode to disarmed */ - arming_res = arming_state_transition(status, safety, ARMING_STATE_STANDBY, armed); + arming_res = arming_state_transition(status, safety, ARMING_STATE_STANDBY, armed, mavlink_fd); if (arming_res != TRANSITION_DENIED) { mavlink_log_info(mavlink_fd, "[cmd] HIL: Reset ARMED state to standby"); @@ -945,8 +945,8 @@ 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_log_info(mavlink_fd, "[cmd] DISARMED by safety switch"); + if (TRANSITION_CHANGED == arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd)) { + mavlink_log_info(mavlink_fd, "#audio DISARMED by safety switch"); } } } @@ -1149,10 +1149,10 @@ int commander_thread_main(int argc, char *argv[]) status.battery_warning = VEHICLE_BATTERY_WARNING_CRITICAL; if (armed.armed) { - arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed); + arming_state_transition(&status, &safety, ARMING_STATE_ARMED_ERROR, &armed, mavlink_fd); } else { - arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed); + arming_state_transition(&status, &safety, ARMING_STATE_STANDBY_ERROR, &armed, mavlink_fd); } status_changed = true; @@ -1163,7 +1163,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) { // XXX check for sensors - arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed); + arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd); } else { // XXX: Add emergency stuff if sensors are lost @@ -1217,7 +1217,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_res = arming_state_transition(&status, &safety, new_arming_state, &armed); + arming_res = arming_state_transition(&status, &safety, new_arming_state, &armed, mavlink_fd); stick_off_counter = 0; } else { @@ -1239,7 +1239,7 @@ int commander_thread_main(int argc, char *argv[]) print_reject_arm("#audio: NOT ARMING: Switch to MANUAL mode first."); } else { - arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed); + arming_res = arming_state_transition(&status, &safety, ARMING_STATE_ARMED, &armed, mavlink_fd); } stick_on_counter = 0; @@ -1941,7 +1941,7 @@ void *commander_low_prio_loop(void *arg) /* try to go to INIT/PREFLIGHT arming state */ // XXX disable interrupts in arming_state_transition - if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed)) { + if (TRANSITION_DENIED == arming_state_transition(&status, &safety, ARMING_STATE_INIT, &armed, mavlink_fd)) { answer_command(cmd, VEHICLE_CMD_RESULT_DENIED); break; } @@ -2004,7 +2004,7 @@ void *commander_low_prio_loop(void *arg) tune_negative(true); } - arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed); + arming_state_transition(&status, &safety, ARMING_STATE_STANDBY, &armed, mavlink_fd); break; } -- cgit v1.2.3 From f76040e55407d3526fb7655ec732304c9ba1dc8b Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 26 Jun 2014 12:54:33 +0200 Subject: mavlink: Always send heartbeat and do not require both topics to update --- src/modules/mavlink/mavlink_messages.cpp | 28 +++++++++++++++------------- 1 file changed, 15 insertions(+), 13 deletions(-) (limited to 'src/modules') diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 4433377c6..b295bf35f 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -226,19 +226,21 @@ protected: struct vehicle_status_s status; struct position_setpoint_triplet_s pos_sp_triplet; - if (status_sub->update(&status) && pos_sp_triplet_sub->update(&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); - } + /* always send the heartbeat, independent of the update status of the topics */ + (void)status_sub->update(&status); + (void)pos_sp_triplet_sub->update(&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); } }; -- cgit v1.2.3