2015-05-13 00:16:45 -03:00
|
|
|
#include "Rover.h"
|
|
|
|
|
2016-05-27 10:04:55 -03:00
|
|
|
#include "GCS_Mavlink.h"
|
|
|
|
|
2017-08-08 02:58:52 -03:00
|
|
|
#include <AP_RangeFinder/RangeFinder_Backend.h>
|
|
|
|
|
2018-03-22 06:21:07 -03:00
|
|
|
MAV_TYPE GCS_MAVLINK_Rover::frame_type() const
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2018-03-22 06:21:07 -03:00
|
|
|
if (rover.is_boat()) {
|
|
|
|
return MAV_TYPE_SURFACE_BOAT;
|
2013-02-08 22:11:43 -04:00
|
|
|
}
|
2018-03-22 06:21:07 -03:00
|
|
|
return MAV_TYPE_GROUND_ROVER;
|
|
|
|
}
|
|
|
|
|
|
|
|
MAV_MODE GCS_MAVLINK_Rover::base_mode() const
|
|
|
|
{
|
2018-04-03 11:35:23 -03:00
|
|
|
uint8_t _base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
2012-04-30 04:17:14 -03:00
|
|
|
|
|
|
|
// work out the base_mode. This value is not very useful
|
|
|
|
// for APM, but we calculate it as best we can so a generic
|
|
|
|
// MAVLink enabled ground station can work out something about
|
|
|
|
// what the MAV is up to. The actual bit values are highly
|
|
|
|
// ambiguous for most of the APM flight modes. In practice, you
|
|
|
|
// only get useful information from the custom_mode, which maps to
|
|
|
|
// the APM flight mode and has a well defined meaning in the
|
|
|
|
// ArduPlane documentation
|
2018-03-22 06:21:07 -03:00
|
|
|
if (rover.control_mode->has_manual_input()) {
|
2018-04-03 11:35:23 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2018-03-22 06:21:07 -03:00
|
|
|
if (rover.control_mode->is_autopilot_mode()) {
|
2018-04-03 11:35:23 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_GUIDED_ENABLED;
|
2017-07-18 23:19:08 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
#if defined(ENABLE_STICK_MIXING) && (ENABLE_STICK_MIXING == ENABLED) // TODO ???? Remove !
|
|
|
|
if (control_mode->stick_mixing_enabled()) {
|
2012-04-30 04:17:14 -03:00
|
|
|
// all modes except INITIALISING have some form of manual
|
|
|
|
// override if stick mixing is enabled
|
2018-04-03 11:35:23 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
2018-04-03 11:35:23 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_HIL_ENABLED;
|
2012-04-30 04:17:14 -03:00
|
|
|
#endif
|
2018-03-22 06:21:07 -03:00
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
// we are armed if we are not initialising
|
2018-03-22 06:21:07 -03:00
|
|
|
if (rover.control_mode != &rover.mode_initializing && rover.arming.is_armed()) {
|
2018-04-03 11:35:23 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_SAFETY_ARMED;
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// indicate we have set a custom mode
|
2018-04-03 11:35:23 -03:00
|
|
|
_base_mode |= MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2018-04-03 11:35:23 -03:00
|
|
|
return (MAV_MODE)_base_mode;
|
2018-03-22 06:21:07 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
uint32_t GCS_MAVLINK_Rover::custom_mode() const
|
|
|
|
{
|
|
|
|
return rover.control_mode->mode_number();
|
|
|
|
}
|
|
|
|
|
|
|
|
MAV_STATE GCS_MAVLINK_Rover::system_status() const
|
|
|
|
{
|
|
|
|
if (rover.failsafe.triggered != 0) {
|
|
|
|
return MAV_STATE_CRITICAL;
|
|
|
|
}
|
|
|
|
if (rover.control_mode == &rover.mode_initializing) {
|
|
|
|
return MAV_STATE_CALIBRATING;
|
|
|
|
}
|
|
|
|
if (rover.control_mode == &rover.mode_hold) {
|
|
|
|
return MAV_STATE_STANDBY;
|
|
|
|
}
|
|
|
|
|
|
|
|
return MAV_STATE_ACTIVE;
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::send_attitude(mavlink_channel_t chan)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-01-31 06:12:26 -04:00
|
|
|
const Vector3f omega = ahrs.get_gyro();
|
2012-04-30 04:17:14 -03:00
|
|
|
mavlink_msg_attitude_send(
|
|
|
|
chan,
|
2012-12-18 15:30:42 -04:00
|
|
|
millis(),
|
2012-04-30 04:17:14 -03:00
|
|
|
ahrs.roll,
|
2012-11-17 02:45:20 -04:00
|
|
|
ahrs.pitch,
|
|
|
|
ahrs.yaw,
|
2012-04-30 04:17:14 -03:00
|
|
|
omega.x,
|
|
|
|
omega.y,
|
|
|
|
omega.z);
|
|
|
|
}
|
|
|
|
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::send_extended_status1(mavlink_channel_t chan)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2013-10-02 03:07:28 -03:00
|
|
|
int16_t battery_current = -1;
|
|
|
|
int8_t battery_remaining = -1;
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-03-18 08:12:11 -03:00
|
|
|
if (battery.has_current() && battery.healthy()) {
|
2013-10-02 03:07:28 -03:00
|
|
|
battery_remaining = battery.capacity_remaining_pct();
|
|
|
|
battery_current = battery.current_amps() * 100;
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2016-10-27 23:20:56 -03:00
|
|
|
update_sensor_status_flags();
|
2015-03-08 18:25:44 -03:00
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
mavlink_msg_sys_status_send(
|
|
|
|
chan,
|
|
|
|
control_sensors_present,
|
|
|
|
control_sensors_enabled,
|
|
|
|
control_sensors_health,
|
2017-07-30 02:09:16 -03:00
|
|
|
static_cast<uint16_t>(scheduler.load_average() * 1000),
|
2016-11-23 13:13:56 -04:00
|
|
|
battery.voltage() * 1000, // mV
|
2012-04-30 04:17:14 -03:00
|
|
|
battery_current, // in 10mA units
|
|
|
|
battery_remaining, // in %
|
2016-11-23 13:13:56 -04:00
|
|
|
0, // comm drops %,
|
|
|
|
0, // comm drops in pkts,
|
2012-04-30 04:17:14 -03:00
|
|
|
0, 0, 0, 0);
|
|
|
|
}
|
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
void Rover::send_location(mavlink_channel_t chan)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2018-02-07 19:11:59 -04:00
|
|
|
const uint32_t now = AP_HAL::millis();
|
|
|
|
Vector3f vel;
|
|
|
|
ahrs.get_velocity_NED(vel);
|
2012-04-30 04:17:14 -03:00
|
|
|
mavlink_msg_global_position_int_send(
|
|
|
|
chan,
|
2018-02-07 19:11:59 -04:00
|
|
|
now,
|
2016-11-23 13:13:56 -04:00
|
|
|
current_loc.lat, // in 1E7 degrees
|
|
|
|
current_loc.lng, // in 1E7 degrees
|
|
|
|
current_loc.alt * 10UL, // millimeters above sea level
|
2017-09-18 04:45:13 -03:00
|
|
|
(current_loc.alt - home.alt) * 10, // millimeters above home
|
2016-11-23 13:13:56 -04:00
|
|
|
vel.x * 100, // X speed cm/s (+ve North)
|
|
|
|
vel.y * 100, // Y speed cm/s (+ve East)
|
2018-02-07 19:06:08 -04:00
|
|
|
vel.z * 100, // Z speed cm/s (+ve Down)
|
2012-12-18 15:30:42 -04:00
|
|
|
ahrs.yaw_sensor);
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
void Rover::send_nav_controller_output(mavlink_channel_t chan)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
|
|
|
mavlink_msg_nav_controller_output_send(
|
|
|
|
chan,
|
2017-12-07 21:21:44 -04:00
|
|
|
g2.attitude_control.get_desired_lat_accel(),
|
2016-11-23 13:13:56 -04:00
|
|
|
ahrs.groundspeed() * ins.get_gyro().z, // use nav_pitch to hold actual Y accel
|
2013-06-16 20:50:53 -03:00
|
|
|
nav_controller->nav_bearing_cd() * 0.01f,
|
|
|
|
nav_controller->target_bearing_cd() * 0.01f,
|
2017-08-01 20:14:49 -03:00
|
|
|
MIN(control_mode->get_distance_to_destination(), UINT16_MAX),
|
2013-09-08 21:18:31 -03:00
|
|
|
0,
|
2017-08-01 20:14:49 -03:00
|
|
|
control_mode->speed_error(),
|
2013-06-16 20:50:53 -03:00
|
|
|
nav_controller->crosstrack_error());
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
void Rover::send_servo_out(mavlink_channel_t chan)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-11-20 19:37:42 -04:00
|
|
|
float motor1, motor3;
|
|
|
|
if (g2.motors.have_skid_steering()) {
|
|
|
|
motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleLeft) / 1000.0f);
|
|
|
|
motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttleRight) / 1000.0f);
|
|
|
|
} else {
|
|
|
|
motor1 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_steering) / 4500.0f);
|
|
|
|
motor3 = 10000 * (SRV_Channels::get_output_scaled(SRV_Channel::k_throttle) / 100.0f);
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
mavlink_msg_rc_channels_scaled_send(
|
|
|
|
chan,
|
|
|
|
millis(),
|
2016-11-23 13:13:56 -04:00
|
|
|
0, // port 0
|
2017-11-20 19:37:42 -04:00
|
|
|
motor1,
|
2013-02-07 18:21:22 -04:00
|
|
|
0,
|
2017-11-20 19:37:42 -04:00
|
|
|
motor3,
|
2013-02-07 18:21:22 -04:00
|
|
|
0,
|
2012-04-30 04:17:14 -03:00
|
|
|
0,
|
|
|
|
0,
|
|
|
|
0,
|
|
|
|
0,
|
2012-12-18 15:30:42 -04:00
|
|
|
receiver_rssi);
|
2015-02-05 02:23:49 -04:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
void Rover::send_vfr_hud(mavlink_channel_t chan)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
|
|
|
mavlink_msg_vfr_hud_send(
|
|
|
|
chan,
|
2014-03-30 22:01:54 -03:00
|
|
|
gps.ground_speed(),
|
2016-05-31 08:23:01 -03:00
|
|
|
ahrs.groundspeed(),
|
2012-11-17 02:45:20 -04:00
|
|
|
(ahrs.yaw_sensor / 100) % 360,
|
2017-07-06 00:06:20 -03:00
|
|
|
g2.motors.get_throttle(),
|
2017-01-31 05:46:32 -04:00
|
|
|
current_loc.alt / 100.0f,
|
2012-04-30 04:17:14 -03:00
|
|
|
0);
|
|
|
|
}
|
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
// report simulator state
|
2015-05-12 04:00:25 -03:00
|
|
|
void Rover::send_simstate(mavlink_channel_t chan)
|
2012-05-14 15:33:03 -03:00
|
|
|
{
|
2015-05-04 03:18:29 -03:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2012-11-17 02:45:20 -04:00
|
|
|
sitl.simstate_send(chan);
|
2012-05-14 15:33:03 -03:00
|
|
|
#endif
|
2013-04-19 18:29:57 -03:00
|
|
|
}
|
2012-05-14 15:33:03 -03:00
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
void Rover::send_rangefinder(mavlink_channel_t chan)
|
2013-02-28 21:00:48 -04:00
|
|
|
{
|
2017-08-08 02:58:52 -03:00
|
|
|
float distance_cm;
|
|
|
|
float voltage;
|
|
|
|
bool got_one = false;
|
|
|
|
|
|
|
|
// report smaller distance of all rangefinders
|
|
|
|
for (uint8_t i=0; i<rangefinder.num_sensors(); i++) {
|
|
|
|
AP_RangeFinder_Backend *s = rangefinder.get_backend(i);
|
|
|
|
if (s == nullptr) {
|
|
|
|
continue;
|
2015-04-17 03:41:00 -03:00
|
|
|
}
|
2017-08-08 02:58:52 -03:00
|
|
|
if (!got_one ||
|
|
|
|
s->distance_cm() < distance_cm) {
|
|
|
|
distance_cm = s->distance_cm();
|
|
|
|
voltage = s->voltage_mv();
|
|
|
|
got_one = true;
|
2013-03-28 21:00:41 -03:00
|
|
|
}
|
|
|
|
}
|
2017-08-08 02:58:52 -03:00
|
|
|
if (!got_one) {
|
|
|
|
// no relevant data found
|
|
|
|
return;
|
|
|
|
}
|
2015-04-17 03:41:00 -03:00
|
|
|
|
2013-02-28 21:00:48 -04:00
|
|
|
mavlink_msg_rangefinder_send(
|
|
|
|
chan,
|
2013-03-28 21:00:41 -03:00
|
|
|
distance_cm * 0.01f,
|
|
|
|
voltage);
|
2013-02-28 21:00:48 -04:00
|
|
|
}
|
|
|
|
|
2015-06-18 04:37:59 -03:00
|
|
|
/*
|
|
|
|
send PID tuning message
|
|
|
|
*/
|
|
|
|
void Rover::send_pid_tuning(mavlink_channel_t chan)
|
|
|
|
{
|
2016-05-29 20:44:23 -03:00
|
|
|
const DataFlash_Class::PID_Info *pid_info;
|
2018-01-01 02:27:39 -04:00
|
|
|
// steering PID
|
|
|
|
if (g.gcs_pid_mask & 1) {
|
2017-08-08 02:37:21 -03:00
|
|
|
pid_info = &g2.attitude_control.get_steering_rate_pid().get_pid_info();
|
2016-11-23 13:13:56 -04:00
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_STEER,
|
2017-10-25 09:17:51 -03:00
|
|
|
degrees(pid_info->desired),
|
|
|
|
degrees(ahrs.get_yaw_rate_earth()),
|
2016-05-29 20:44:23 -03:00
|
|
|
pid_info->FF,
|
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
|
|
|
pid_info->D);
|
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2018-01-01 02:27:39 -04:00
|
|
|
// speed to throttle PID
|
|
|
|
if (g.gcs_pid_mask & 2) {
|
2017-08-08 21:24:30 -03:00
|
|
|
pid_info = &g2.attitude_control.get_throttle_speed_pid().get_pid_info();
|
2017-10-25 09:17:51 -03:00
|
|
|
float speed = 0.0f;
|
|
|
|
g2.attitude_control.get_forward_speed(speed);
|
2016-11-23 13:13:56 -04:00
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
|
2016-05-29 20:44:23 -03:00
|
|
|
pid_info->desired,
|
2017-10-25 09:17:51 -03:00
|
|
|
speed,
|
2016-05-29 20:44:23 -03:00
|
|
|
0,
|
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
|
|
|
pid_info->D);
|
2015-06-18 04:37:59 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-08-16 07:02:56 -03:00
|
|
|
void Rover::send_fence_status(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
fence_send_mavlink_status(chan);
|
|
|
|
}
|
|
|
|
|
2017-07-20 23:56:39 -03:00
|
|
|
void Rover::send_wheel_encoder(mavlink_channel_t chan)
|
|
|
|
{
|
|
|
|
// send wheel encoder data using rpm message
|
|
|
|
if (g2.wheel_encoder.enabled(0) || g2.wheel_encoder.enabled(1)) {
|
|
|
|
mavlink_msg_rpm_send(chan, wheel_encoder_rpm[0], wheel_encoder_rpm[1]);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-07-12 04:42:48 -03:00
|
|
|
uint8_t GCS_MAVLINK_Rover::sysid_my_gcs() const
|
|
|
|
{
|
|
|
|
return rover.g.sysid_my_gcs;
|
|
|
|
}
|
|
|
|
|
2016-05-29 21:08:46 -03:00
|
|
|
uint32_t GCS_MAVLINK_Rover::telem_delay() const
|
2012-08-29 20:36:18 -03:00
|
|
|
{
|
2017-03-30 11:07:24 -03:00
|
|
|
return static_cast<uint32_t>(rover.g.telem_delay);
|
2012-08-29 20:36:18 -03:00
|
|
|
}
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
// try to send a message, return false if it won't fit in the serial tx buffer
|
2016-05-27 10:04:55 -03:00
|
|
|
bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-07-12 05:10:38 -03:00
|
|
|
if (telemetry_delayed()) {
|
2012-04-30 04:17:14 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2013-10-27 20:33:52 -03:00
|
|
|
// if we don't have at least 1ms remaining before the main loop
|
|
|
|
// wants to fire then don't send a mavlink message. We want to
|
|
|
|
// prioritise the main flight control loop over communications
|
2015-05-12 04:00:25 -03:00
|
|
|
if (!rover.in_mavlink_delay && rover.scheduler.time_available_usec() < 1200) {
|
2017-08-20 23:32:34 -03:00
|
|
|
gcs().set_out_of_time(true);
|
2013-10-27 20:33:52 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
switch (id) {
|
|
|
|
case MSG_HEARTBEAT:
|
|
|
|
CHECK_PAYLOAD_SIZE(HEARTBEAT);
|
2016-11-23 13:13:56 -04:00
|
|
|
last_heartbeat_time = AP_HAL::millis();
|
2018-03-22 06:21:07 -03:00
|
|
|
send_heartbeat();
|
2012-04-30 04:17:14 -03:00
|
|
|
return true;
|
|
|
|
|
|
|
|
case MSG_EXTENDED_STATUS1:
|
2017-06-27 23:32:01 -03:00
|
|
|
// send extended status only once vehicle has been initialised
|
|
|
|
// to avoid unnecessary errors being reported to user
|
|
|
|
if (initialised) {
|
|
|
|
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
|
|
|
rover.send_extended_status1(chan);
|
|
|
|
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
|
|
|
send_power_status();
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_ATTITUDE:
|
|
|
|
CHECK_PAYLOAD_SIZE(ATTITUDE);
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.send_attitude(chan);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_LOCATION:
|
|
|
|
CHECK_PAYLOAD_SIZE(GLOBAL_POSITION_INT);
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.send_location(chan);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_NAV_CONTROLLER_OUTPUT:
|
2017-07-18 23:19:08 -03:00
|
|
|
if (rover.control_mode->is_autopilot_mode()) {
|
2012-04-30 04:17:14 -03:00
|
|
|
CHECK_PAYLOAD_SIZE(NAV_CONTROLLER_OUTPUT);
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.send_nav_controller_output(chan);
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_SERVO_OUT:
|
|
|
|
CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED);
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.send_servo_out(chan);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_RADIO_IN:
|
2016-10-13 07:24:13 -03:00
|
|
|
CHECK_PAYLOAD_SIZE(RC_CHANNELS);
|
2016-05-16 19:27:01 -03:00
|
|
|
send_radio_in(rover.receiver_rssi);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
2017-01-10 11:19:22 -04:00
|
|
|
case MSG_SERVO_OUTPUT_RAW:
|
2012-04-30 04:17:14 -03:00
|
|
|
CHECK_PAYLOAD_SIZE(SERVO_OUTPUT_RAW);
|
2016-07-15 07:04:19 -03:00
|
|
|
send_servo_output_raw(false);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_VFR_HUD:
|
|
|
|
CHECK_PAYLOAD_SIZE(VFR_HUD);
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.send_vfr_hud(chan);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case MSG_RAW_IMU1:
|
|
|
|
CHECK_PAYLOAD_SIZE(RAW_IMU);
|
2016-05-16 19:27:01 -03:00
|
|
|
send_raw_imu(rover.ins, rover.compass);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
2018-01-21 17:46:04 -04:00
|
|
|
case MSG_RAW_IMU2:
|
|
|
|
CHECK_PAYLOAD_SIZE(SCALED_PRESSURE);
|
2018-03-05 16:36:56 -04:00
|
|
|
send_scaled_pressure();
|
2018-01-21 17:46:04 -04:00
|
|
|
break;
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
case MSG_RAW_IMU3:
|
|
|
|
CHECK_PAYLOAD_SIZE(SENSOR_OFFSETS);
|
2018-03-05 16:36:56 -04:00
|
|
|
send_sensor_offsets(rover.ins, rover.compass);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
case MSG_SIMSTATE:
|
|
|
|
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.send_simstate(chan);
|
2012-05-14 15:33:03 -03:00
|
|
|
break;
|
|
|
|
|
2013-02-28 21:00:48 -04:00
|
|
|
case MSG_RANGEFINDER:
|
|
|
|
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.send_rangefinder(chan);
|
2017-07-13 08:36:44 -03:00
|
|
|
send_distance_sensor(rover.rangefinder);
|
2017-08-16 07:57:42 -03:00
|
|
|
send_proximity(rover.g2.proximity);
|
2013-02-28 21:00:48 -04:00
|
|
|
break;
|
|
|
|
|
2017-07-20 23:56:39 -03:00
|
|
|
case MSG_RPM:
|
|
|
|
CHECK_PAYLOAD_SIZE(RPM);
|
|
|
|
rover.send_wheel_encoder(chan);
|
|
|
|
break;
|
|
|
|
|
2014-11-17 19:43:11 -04:00
|
|
|
case MSG_MOUNT_STATUS:
|
|
|
|
#if MOUNT == ENABLED
|
|
|
|
CHECK_PAYLOAD_SIZE(MOUNT_STATUS);
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.camera_mount.status_msg(chan);
|
2016-11-23 13:13:56 -04:00
|
|
|
#endif // MOUNT == ENABLED
|
2014-11-17 19:43:11 -04:00
|
|
|
break;
|
|
|
|
|
2017-08-16 07:02:56 -03:00
|
|
|
case MSG_FENCE_STATUS:
|
|
|
|
CHECK_PAYLOAD_SIZE(FENCE_STATUS);
|
|
|
|
rover.send_fence_status(chan);
|
|
|
|
break;
|
|
|
|
|
2016-04-04 21:40:40 -03:00
|
|
|
case MSG_VIBRATION:
|
|
|
|
CHECK_PAYLOAD_SIZE(VIBRATION);
|
|
|
|
send_vibration(rover.ins);
|
|
|
|
break;
|
|
|
|
|
2015-01-06 00:17:56 -04:00
|
|
|
case MSG_BATTERY2:
|
|
|
|
CHECK_PAYLOAD_SIZE(BATTERY2);
|
2016-05-16 19:27:01 -03:00
|
|
|
send_battery2(rover.battery);
|
2015-01-06 00:17:56 -04:00
|
|
|
break;
|
2015-01-06 00:28:38 -04:00
|
|
|
|
2015-03-12 00:31:45 -03:00
|
|
|
case MSG_EKF_STATUS_REPORT:
|
|
|
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
|
|
|
CHECK_PAYLOAD_SIZE(EKF_STATUS_REPORT);
|
2015-09-28 21:59:28 -03:00
|
|
|
rover.ahrs.send_ekf_status_report(chan);
|
2015-03-12 00:31:45 -03:00
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
|
2015-06-18 04:37:59 -03:00
|
|
|
case MSG_PID_TUNING:
|
|
|
|
CHECK_PAYLOAD_SIZE(PID_TUNING);
|
|
|
|
rover.send_pid_tuning(chan);
|
|
|
|
break;
|
|
|
|
|
2017-04-07 17:14:22 -03:00
|
|
|
case MSG_BATTERY_STATUS:
|
|
|
|
send_battery_status(rover.battery);
|
|
|
|
break;
|
|
|
|
|
2017-07-18 03:43:57 -03:00
|
|
|
default:
|
|
|
|
return GCS_MAVLINK::try_send_message(id);
|
2015-07-30 22:24:32 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2013-10-20 19:32:39 -03:00
|
|
|
/*
|
|
|
|
default stream rates to 1Hz
|
|
|
|
*/
|
2015-10-25 14:03:46 -03:00
|
|
|
const AP_Param::GroupInfo GCS_MAVLINK::var_info[] = {
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Param: RAW_SENS
|
2013-10-20 19:32:39 -03:00
|
|
|
// @DisplayName: Raw sensor stream rate
|
|
|
|
// @Description: Raw sensor stream rate to ground station
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2013-10-20 19:32:39 -03:00
|
|
|
// @Range: 0 10
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2013-10-20 19:32:39 -03:00
|
|
|
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK, streamRates[0], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: EXT_STAT
|
2013-10-20 19:32:39 -03:00
|
|
|
// @DisplayName: Extended status stream rate to ground station
|
|
|
|
// @Description: Extended status stream rate to ground station
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2013-10-20 19:32:39 -03:00
|
|
|
// @Range: 0 10
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2013-10-20 19:32:39 -03:00
|
|
|
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK, streamRates[1], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: RC_CHAN
|
2013-10-20 19:32:39 -03:00
|
|
|
// @DisplayName: RC Channel stream rate to ground station
|
|
|
|
// @Description: RC Channel stream rate to ground station
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2013-10-20 19:32:39 -03:00
|
|
|
// @Range: 0 10
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2013-10-20 19:32:39 -03:00
|
|
|
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK, streamRates[2], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: RAW_CTRL
|
2013-10-20 19:32:39 -03:00
|
|
|
// @DisplayName: Raw Control stream rate to ground station
|
|
|
|
// @Description: Raw Control stream rate to ground station
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2013-10-20 19:32:39 -03:00
|
|
|
// @Range: 0 10
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2013-10-20 19:32:39 -03:00
|
|
|
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK, streamRates[3], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: POSITION
|
2013-10-20 19:32:39 -03:00
|
|
|
// @DisplayName: Position stream rate to ground station
|
|
|
|
// @Description: Position stream rate to ground station
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2013-10-20 19:32:39 -03:00
|
|
|
// @Range: 0 10
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2013-10-20 19:32:39 -03:00
|
|
|
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK, streamRates[4], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: EXTRA1
|
2013-10-20 19:32:39 -03:00
|
|
|
// @DisplayName: Extra data type 1 stream rate to ground station
|
|
|
|
// @Description: Extra data type 1 stream rate to ground station
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2013-10-20 19:32:39 -03:00
|
|
|
// @Range: 0 10
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2013-10-20 19:32:39 -03:00
|
|
|
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK, streamRates[5], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: EXTRA2
|
2013-10-20 19:32:39 -03:00
|
|
|
// @DisplayName: Extra data type 2 stream rate to ground station
|
|
|
|
// @Description: Extra data type 2 stream rate to ground station
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2013-10-20 19:32:39 -03:00
|
|
|
// @Range: 0 10
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2013-10-20 19:32:39 -03:00
|
|
|
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK, streamRates[6], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: EXTRA3
|
2013-10-20 19:32:39 -03:00
|
|
|
// @DisplayName: Extra data type 3 stream rate to ground station
|
|
|
|
// @Description: Extra data type 3 stream rate to ground station
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2013-10-20 19:32:39 -03:00
|
|
|
// @Range: 0 10
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2013-10-20 19:32:39 -03:00
|
|
|
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK, streamRates[7], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: PARAMS
|
2013-10-20 19:32:39 -03:00
|
|
|
// @DisplayName: Parameter stream rate to ground station
|
|
|
|
// @Description: Parameter stream rate to ground station
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2013-10-20 19:32:39 -03:00
|
|
|
// @Range: 0 10
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2013-10-27 20:33:52 -03:00
|
|
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK, streamRates[8], 10),
|
2012-04-30 04:17:14 -03:00
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
|
|
|
void
|
2016-05-27 10:04:55 -03:00
|
|
|
GCS_MAVLINK_Rover::data_stream_send(void)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-08-20 23:32:34 -03:00
|
|
|
gcs().set_out_of_time(false);
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2017-04-29 01:36:42 -03:00
|
|
|
send_queued_parameters();
|
2012-12-18 15:30:42 -04:00
|
|
|
|
2017-08-20 23:32:34 -03:00
|
|
|
if (gcs().out_of_time()) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2015-05-12 04:00:25 -03:00
|
|
|
if (rover.in_mavlink_delay) {
|
2012-12-18 15:30:42 -04:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
|
|
|
// in HIL we need to keep sending servo values to ensure
|
|
|
|
// the simulator doesn't pause, otherwise our sensor
|
|
|
|
// calibration could stall
|
|
|
|
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
|
|
|
|
send_message(MSG_SERVO_OUT);
|
|
|
|
}
|
2012-12-18 16:17:06 -04:00
|
|
|
if (stream_trigger(STREAM_RC_CHANNELS)) {
|
2017-01-10 11:19:22 -04:00
|
|
|
send_message(MSG_SERVO_OUTPUT_RAW);
|
2012-12-18 16:17:06 -04:00
|
|
|
}
|
2012-12-18 15:30:42 -04:00
|
|
|
#endif
|
2012-12-18 16:17:06 -04:00
|
|
|
// don't send any other stream types while in the delay callback
|
2012-05-14 15:33:03 -03:00
|
|
|
return;
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-08-20 23:32:34 -03:00
|
|
|
if (gcs().out_of_time()) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
if (stream_trigger(STREAM_RAW_SENSORS)) {
|
|
|
|
send_message(MSG_RAW_IMU1);
|
2018-01-21 17:46:04 -04:00
|
|
|
send_message(MSG_RAW_IMU2);
|
2012-05-14 15:33:03 -03:00
|
|
|
send_message(MSG_RAW_IMU3);
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-08-20 23:32:34 -03:00
|
|
|
if (gcs().out_of_time()) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
if (stream_trigger(STREAM_EXTENDED_STATUS)) {
|
|
|
|
send_message(MSG_EXTENDED_STATUS1);
|
|
|
|
send_message(MSG_EXTENDED_STATUS2);
|
|
|
|
send_message(MSG_CURRENT_WAYPOINT);
|
2017-08-08 07:01:35 -03:00
|
|
|
send_message(MSG_GPS_RAW);
|
|
|
|
send_message(MSG_GPS_RTK);
|
|
|
|
send_message(MSG_GPS2_RAW);
|
|
|
|
send_message(MSG_GPS2_RTK);
|
2012-05-14 15:33:03 -03:00
|
|
|
send_message(MSG_NAV_CONTROLLER_OUTPUT);
|
2017-08-16 07:02:56 -03:00
|
|
|
send_message(MSG_FENCE_STATUS);
|
2012-05-14 15:33:03 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-08-20 23:32:34 -03:00
|
|
|
if (gcs().out_of_time()) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
if (stream_trigger(STREAM_POSITION)) {
|
|
|
|
// sent with GPS read
|
|
|
|
send_message(MSG_LOCATION);
|
2015-04-05 13:25:28 -03:00
|
|
|
send_message(MSG_LOCAL_POSITION);
|
2012-05-14 15:33:03 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-08-20 23:32:34 -03:00
|
|
|
if (gcs().out_of_time()) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
if (stream_trigger(STREAM_RAW_CONTROLLER)) {
|
|
|
|
send_message(MSG_SERVO_OUT);
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-08-20 23:32:34 -03:00
|
|
|
if (gcs().out_of_time()) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
if (stream_trigger(STREAM_RC_CHANNELS)) {
|
2017-01-10 11:19:22 -04:00
|
|
|
send_message(MSG_SERVO_OUTPUT_RAW);
|
2012-05-14 15:33:03 -03:00
|
|
|
send_message(MSG_RADIO_IN);
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-08-20 23:32:34 -03:00
|
|
|
if (gcs().out_of_time()) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
if (stream_trigger(STREAM_EXTRA1)) {
|
|
|
|
send_message(MSG_ATTITUDE);
|
|
|
|
send_message(MSG_SIMSTATE);
|
2017-11-28 07:20:24 -04:00
|
|
|
send_message(MSG_PID_TUNING);
|
2012-05-14 15:33:03 -03:00
|
|
|
}
|
2016-11-23 13:13:56 -04:00
|
|
|
|
2017-08-20 23:32:34 -03:00
|
|
|
if (gcs().out_of_time()) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
if (stream_trigger(STREAM_EXTRA2)) {
|
|
|
|
send_message(MSG_VFR_HUD);
|
|
|
|
}
|
|
|
|
|
2017-08-20 23:32:34 -03:00
|
|
|
if (gcs().out_of_time()) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2013-10-27 20:33:52 -03:00
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
if (stream_trigger(STREAM_EXTRA3)) {
|
|
|
|
send_message(MSG_AHRS);
|
|
|
|
send_message(MSG_HWSTATUS);
|
2013-02-28 21:00:48 -04:00
|
|
|
send_message(MSG_RANGEFINDER);
|
2013-10-23 08:15:37 -03:00
|
|
|
send_message(MSG_SYSTEM_TIME);
|
2015-01-06 00:17:56 -04:00
|
|
|
send_message(MSG_BATTERY2);
|
2017-04-07 17:14:22 -03:00
|
|
|
send_message(MSG_BATTERY_STATUS);
|
2015-07-30 22:24:32 -03:00
|
|
|
send_message(MSG_MAG_CAL_REPORT);
|
|
|
|
send_message(MSG_MAG_CAL_PROGRESS);
|
2014-11-17 19:43:11 -04:00
|
|
|
send_message(MSG_MOUNT_STATUS);
|
2015-03-12 00:31:45 -03:00
|
|
|
send_message(MSG_EKF_STATUS_REPORT);
|
2016-04-04 21:40:40 -03:00
|
|
|
send_message(MSG_VIBRATION);
|
2017-07-20 23:56:39 -03:00
|
|
|
send_message(MSG_RPM);
|
2012-05-14 15:33:03 -03:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
|
2016-05-27 10:04:55 -03:00
|
|
|
bool GCS_MAVLINK_Rover::handle_guided_request(AP_Mission::Mission_Command &cmd)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-07-18 23:19:08 -03:00
|
|
|
if (rover.control_mode != &rover.mode_guided) {
|
2015-06-03 09:31:31 -03:00
|
|
|
// only accept position updates when in GUIDED mode
|
2016-04-26 07:17:40 -03:00
|
|
|
return false;
|
2015-06-03 09:31:31 -03:00
|
|
|
}
|
2014-03-18 20:06:58 -03:00
|
|
|
|
|
|
|
// make any new wp uploaded instant (in case we are already in Guided mode)
|
2017-08-01 20:10:38 -03:00
|
|
|
rover.mode_guided.set_desired_location(cmd.content.location);
|
2016-04-26 07:17:40 -03:00
|
|
|
return true;
|
2014-03-18 20:06:58 -03:00
|
|
|
}
|
|
|
|
|
2016-05-27 10:04:55 -03:00
|
|
|
void GCS_MAVLINK_Rover::handle_change_alt_request(AP_Mission::Mission_Command &cmd)
|
2014-03-18 20:06:58 -03:00
|
|
|
{
|
|
|
|
// nothing to do
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2018-03-17 05:19:30 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_long_t &packet)
|
|
|
|
{
|
|
|
|
if (is_equal(packet.param4, 1.0f)) {
|
|
|
|
rover.trim_radio();
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
|
|
|
|
return GCS_MAVLINK::_handle_command_preflight_calibration(packet);
|
|
|
|
}
|
|
|
|
|
2016-05-27 10:04:55 -03:00
|
|
|
void GCS_MAVLINK_Rover::handleMessage(mavlink_message_t* msg)
|
2014-03-18 20:06:58 -03:00
|
|
|
{
|
2012-04-30 04:17:14 -03:00
|
|
|
switch (msg->msgid) {
|
2017-09-18 02:37:37 -03:00
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
|
|
|
|
{
|
2014-03-18 18:54:16 -03:00
|
|
|
handle_request_data_stream(msg, true);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-08-25 22:28:49 -03:00
|
|
|
case MAVLINK_MSG_ID_COMMAND_INT: {
|
|
|
|
// decode packet
|
|
|
|
mavlink_command_int_t packet;
|
|
|
|
mavlink_msg_command_int_decode(msg, &packet);
|
2017-11-27 02:19:58 -04:00
|
|
|
MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
|
2016-08-25 22:28:49 -03:00
|
|
|
|
2016-11-23 13:13:56 -04:00
|
|
|
switch (packet.command) {
|
2017-09-19 21:22:15 -03:00
|
|
|
|
|
|
|
case MAV_CMD_DO_SET_HOME: {
|
|
|
|
// assume failure
|
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
if (is_equal(packet.param1, 1.0f)) {
|
|
|
|
// if param1 is 1, use current location
|
|
|
|
if (rover.set_home_to_current_location(true)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
// ensure param1 is zero
|
|
|
|
if (!is_zero(packet.param1)) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
// check frame type is supported
|
|
|
|
if (packet.frame != MAV_FRAME_GLOBAL &&
|
|
|
|
packet.frame != MAV_FRAME_GLOBAL_INT &&
|
|
|
|
packet.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT &&
|
|
|
|
packet.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
// sanity check location
|
|
|
|
if (!check_latlng(packet.x, packet.y)) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
Location new_home_loc {};
|
|
|
|
new_home_loc.lat = packet.x;
|
|
|
|
new_home_loc.lng = packet.y;
|
|
|
|
new_home_loc.alt = packet.z * 100;
|
|
|
|
// handle relative altitude
|
|
|
|
if (packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT || packet.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT) {
|
2018-03-15 22:06:46 -03:00
|
|
|
if (!rover.ahrs.home_is_set()) {
|
2017-09-19 21:22:15 -03:00
|
|
|
// cannot use relative altitude if home is not set
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
new_home_loc.alt += rover.ahrs.get_home().alt;
|
|
|
|
}
|
|
|
|
if (rover.set_home(new_home_loc, true)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-08-25 22:28:49 -03:00
|
|
|
#if MOUNT == ENABLED
|
|
|
|
case MAV_CMD_DO_SET_ROI: {
|
|
|
|
// param1 : /* Region of interest mode (not used)*/
|
|
|
|
// param2 : /* MISSION index/ target ID (not used)*/
|
|
|
|
// param3 : /* ROI index (not used)*/
|
|
|
|
// param4 : /* empty */
|
|
|
|
// x : lat
|
|
|
|
// y : lon
|
|
|
|
// z : alt
|
|
|
|
// sanity check location
|
|
|
|
if (!check_latlng(packet.x, packet.y)) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
Location roi_loc;
|
|
|
|
roi_loc.lat = packet.x;
|
|
|
|
roi_loc.lng = packet.y;
|
|
|
|
roi_loc.alt = (int32_t)(packet.z * 100.0f);
|
|
|
|
if (roi_loc.lat == 0 && roi_loc.lng == 0 && roi_loc.alt == 0) {
|
|
|
|
// switch off the camera tracking if enabled
|
|
|
|
if (rover.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
|
|
|
|
rover.camera_mount.set_mode_to_default();
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// send the command to the camera mount
|
|
|
|
rover.camera_mount.set_roi_target(roi_loc);
|
|
|
|
}
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
|
|
|
default:
|
|
|
|
result = MAV_RESULT_UNSUPPORTED;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// send ACK or NAK
|
|
|
|
mavlink_msg_command_ack_send_buf(msg, chan, packet.command, result);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
case MAVLINK_MSG_ID_COMMAND_LONG:
|
|
|
|
{
|
|
|
|
// decode
|
|
|
|
mavlink_command_long_t packet;
|
|
|
|
mavlink_msg_command_long_decode(msg, &packet);
|
|
|
|
|
2017-11-27 02:19:58 -04:00
|
|
|
MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
|
2012-04-30 04:17:14 -03:00
|
|
|
|
|
|
|
// do command
|
|
|
|
|
2016-11-23 13:13:56 -04:00
|
|
|
switch (packet.command) {
|
2015-06-10 03:45:56 -03:00
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
2017-07-24 14:05:59 -03:00
|
|
|
rover.set_mode(rover.mode_rtl, MODE_REASON_GCS_COMMAND);
|
2012-04-30 04:17:14 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
break;
|
|
|
|
|
2014-07-04 03:54:15 -03:00
|
|
|
#if MOUNT == ENABLED
|
|
|
|
// Sets the region of interest (ROI) for the camera
|
|
|
|
case MAV_CMD_DO_SET_ROI:
|
2015-08-27 02:36:15 -03:00
|
|
|
// sanity check location
|
2016-06-01 19:29:32 -03:00
|
|
|
if (!check_latlng(packet.param5, packet.param6)) {
|
2015-08-27 02:36:15 -03:00
|
|
|
break;
|
|
|
|
}
|
2014-07-04 03:54:15 -03:00
|
|
|
Location roi_loc;
|
|
|
|
roi_loc.lat = (int32_t)(packet.param5 * 1.0e7f);
|
|
|
|
roi_loc.lng = (int32_t)(packet.param6 * 1.0e7f);
|
|
|
|
roi_loc.alt = (int32_t)(packet.param7 * 100.0f);
|
|
|
|
if (roi_loc.lat == 0 && roi_loc.lng == 0 && roi_loc.alt == 0) {
|
|
|
|
// switch off the camera tracking if enabled
|
2015-05-12 04:00:25 -03:00
|
|
|
if (rover.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) {
|
|
|
|
rover.camera_mount.set_mode_to_default();
|
2014-07-04 03:54:15 -03:00
|
|
|
}
|
|
|
|
} else {
|
|
|
|
// send the command to the camera mount
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.camera_mount.set_roi_target(roi_loc);
|
2014-07-04 03:54:15 -03:00
|
|
|
}
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
break;
|
|
|
|
#endif
|
|
|
|
|
2015-09-02 04:46:03 -03:00
|
|
|
case MAV_CMD_DO_MOUNT_CONTROL:
|
|
|
|
#if MOUNT == ENABLED
|
|
|
|
rover.camera_mount.control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7);
|
2016-04-22 08:22:35 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
2015-09-02 04:46:03 -03:00
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
|
2012-05-14 15:33:03 -03:00
|
|
|
case MAV_CMD_MISSION_START:
|
2017-07-24 14:05:59 -03:00
|
|
|
rover.set_mode(rover.mode_auto, MODE_REASON_GCS_COMMAND);
|
2012-05-14 15:33:03 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
2012-12-18 15:30:42 -04:00
|
|
|
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
|
2016-11-23 13:13:56 -04:00
|
|
|
if (is_equal(packet.param1, 1.0f) || is_equal(packet.param1, 3.0f)) {
|
2013-09-03 22:58:41 -03:00
|
|
|
// when packet.param1 == 3 we reboot to hold in bootloader
|
2016-11-23 13:13:56 -04:00
|
|
|
hal.scheduler->reboot(is_equal(packet.param1, 3.0f));
|
2012-12-18 15:30:42 -04:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2015-10-30 02:56:41 -03:00
|
|
|
case MAV_CMD_COMPONENT_ARM_DISARM:
|
2016-11-23 13:13:56 -04:00
|
|
|
if (is_equal(packet.param1, 1.0f)) {
|
2015-10-30 02:56:41 -03:00
|
|
|
// run pre_arm_checks and arm_checks and display failures
|
|
|
|
if (rover.arm_motors(AP_Arming::MAVLINK)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
} else {
|
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
} else if (is_zero(packet.param1)) {
|
|
|
|
if (rover.disarm_motors()) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
} else {
|
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
} else {
|
|
|
|
result = MAV_RESULT_UNSUPPORTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2017-08-16 07:02:56 -03:00
|
|
|
case MAV_CMD_DO_FENCE_ENABLE:
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
switch ((uint16_t)packet.param1) {
|
|
|
|
case 0:
|
|
|
|
rover.g2.fence.enable(false);
|
|
|
|
break;
|
|
|
|
case 1:
|
|
|
|
rover.g2.fence.enable(true);
|
|
|
|
break;
|
|
|
|
default:
|
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2016-03-14 05:08:31 -03:00
|
|
|
case MAV_CMD_DO_SET_HOME:
|
|
|
|
{
|
|
|
|
// param1 : use current (1=use current location, 0=use specified location)
|
|
|
|
// param5 : latitude
|
|
|
|
// param6 : longitude
|
|
|
|
// param7 : altitude
|
2016-11-23 13:13:56 -04:00
|
|
|
result = MAV_RESULT_FAILED; // assume failure
|
|
|
|
if (is_equal(packet.param1, 1.0f)) {
|
2017-06-05 04:55:24 -03:00
|
|
|
if (rover.set_home_to_current_location(true)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
2016-03-14 05:08:31 -03:00
|
|
|
}
|
2017-06-05 04:55:24 -03:00
|
|
|
} else {
|
2017-09-19 21:22:44 -03:00
|
|
|
// ensure param1 is zero
|
|
|
|
if (!is_zero(packet.param1)) {
|
|
|
|
break;
|
|
|
|
}
|
2016-03-14 05:08:31 -03:00
|
|
|
Location new_home_loc {};
|
2017-02-20 09:26:00 -04:00
|
|
|
new_home_loc.lat = static_cast<int32_t>(packet.param5 * 1.0e7f);
|
|
|
|
new_home_loc.lng = static_cast<int32_t>(packet.param6 * 1.0e7f);
|
|
|
|
new_home_loc.alt = static_cast<int32_t>(packet.param7 * 100.0f);
|
2017-06-05 04:55:24 -03:00
|
|
|
if (rover.set_home(new_home_loc, true)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
2016-03-14 05:08:31 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-09-15 09:09:45 -03:00
|
|
|
case MAV_CMD_NAV_SET_YAW_SPEED:
|
|
|
|
{
|
|
|
|
// param1 : yaw angle to adjust direction by in centidegress
|
|
|
|
// param2 : Speed - normalized to 0 .. 1
|
|
|
|
|
|
|
|
// exit if vehicle is not in Guided mode
|
2017-07-18 23:19:08 -03:00
|
|
|
if (rover.control_mode != &rover.mode_guided) {
|
2016-09-15 09:09:45 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-08-01 20:10:38 -03:00
|
|
|
// send yaw change and target speed to guided mode controller
|
2017-12-05 21:41:28 -04:00
|
|
|
const float speed_max = rover.control_mode->get_speed_default();
|
|
|
|
const float target_speed = constrain_float(packet.param2 * speed_max, -speed_max, speed_max);
|
2017-08-01 20:10:38 -03:00
|
|
|
rover.mode_guided.set_desired_heading_delta_and_speed(packet.param1, target_speed);
|
2016-09-15 09:09:45 -03:00
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-11-12 05:49:28 -04:00
|
|
|
case MAV_CMD_ACCELCAL_VEHICLE_POS:
|
|
|
|
result = MAV_RESULT_FAILED;
|
|
|
|
|
|
|
|
if (rover.ins.get_acal()->gcs_vehicle_position(packet.param1)) {
|
|
|
|
result = MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2017-07-14 23:59:28 -03:00
|
|
|
case MAV_CMD_DO_MOTOR_TEST:
|
|
|
|
// param1 : motor sequence number (a number from 1 to max number of motors on the vehicle)
|
|
|
|
// param2 : throttle type (0=throttle percentage, 1=PWM, 2=pilot throttle channel pass-through. See MOTOR_TEST_THROTTLE_TYPE enum)
|
|
|
|
// param3 : throttle (range depends upon param2)
|
|
|
|
// param4 : timeout (in seconds)
|
|
|
|
result = rover.mavlink_motor_test_start(chan, static_cast<uint8_t>(packet.param1),
|
|
|
|
static_cast<uint8_t>(packet.param2),
|
2017-07-15 05:18:46 -03:00
|
|
|
static_cast<int16_t>(packet.param3),
|
2017-07-14 23:59:28 -03:00
|
|
|
packet.param4);
|
|
|
|
break;
|
2016-11-12 05:49:28 -04:00
|
|
|
|
2012-12-18 15:30:42 -04:00
|
|
|
default:
|
2017-07-13 23:04:46 -03:00
|
|
|
result = handle_command_long_message(packet);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2014-03-18 18:54:16 -03:00
|
|
|
mavlink_msg_command_ack_send_buf(
|
|
|
|
msg,
|
2012-04-30 04:17:14 -03:00
|
|
|
chan,
|
|
|
|
packet.command,
|
|
|
|
result);
|
|
|
|
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
|
2012-12-18 07:44:12 -04:00
|
|
|
{
|
|
|
|
// allow override of RC channel values for HIL
|
|
|
|
// or for complete GCS control of switch position
|
|
|
|
// and RC PWM values.
|
2016-11-23 13:13:56 -04:00
|
|
|
if (msg->sysid != rover.g.sysid_my_gcs) { // Only accept control from our gcs
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2012-12-18 07:44:12 -04:00
|
|
|
mavlink_rc_channels_override_t packet;
|
|
|
|
mavlink_msg_rc_channels_override_decode(msg, &packet);
|
|
|
|
|
2018-04-03 23:17:20 -03:00
|
|
|
RC_Channels::set_override(0, packet.chan1_raw);
|
|
|
|
RC_Channels::set_override(1, packet.chan2_raw);
|
|
|
|
RC_Channels::set_override(2, packet.chan3_raw);
|
|
|
|
RC_Channels::set_override(3, packet.chan4_raw);
|
|
|
|
RC_Channels::set_override(4, packet.chan5_raw);
|
|
|
|
RC_Channels::set_override(5, packet.chan6_raw);
|
|
|
|
RC_Channels::set_override(6, packet.chan7_raw);
|
|
|
|
RC_Channels::set_override(7, packet.chan8_raw);
|
2012-12-18 07:44:12 -04:00
|
|
|
|
2015-11-19 23:04:16 -04:00
|
|
|
rover.failsafe.rc_override_timer = AP_HAL::millis();
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.failsafe_trigger(FAILSAFE_EVENT_RC, false);
|
2012-12-18 07:44:12 -04:00
|
|
|
break;
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-04-27 13:03:24 -03:00
|
|
|
case MAVLINK_MSG_ID_MANUAL_CONTROL:
|
|
|
|
{
|
|
|
|
if (msg->sysid != rover.g.sysid_my_gcs) { // Only accept control from our gcs
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
mavlink_manual_control_t packet;
|
|
|
|
mavlink_msg_manual_control_decode(msg, &packet);
|
2018-04-03 20:20:51 -03:00
|
|
|
|
|
|
|
if (packet.target != rover.g.sysid_this_mav) {
|
|
|
|
break; // only accept control aimed at us
|
|
|
|
}
|
2017-04-27 13:03:24 -03:00
|
|
|
|
|
|
|
const int16_t roll = (packet.y == INT16_MAX) ? 0 : rover.channel_steer->get_radio_min() + (rover.channel_steer->get_radio_max() - rover.channel_steer->get_radio_min()) * (packet.y + 1000) / 2000.0f;
|
|
|
|
const int16_t throttle = (packet.z == INT16_MAX) ? 0 : rover.channel_throttle->get_radio_min() + (rover.channel_throttle->get_radio_max() - rover.channel_throttle->get_radio_min()) * (packet.z + 1000) / 2000.0f;
|
2018-04-03 23:17:20 -03:00
|
|
|
RC_Channels::set_override(uint8_t(rover.rcmap.roll() - 1), roll);
|
|
|
|
RC_Channels::set_override(uint8_t(rover.rcmap.throttle() - 1), throttle);
|
2017-04-27 13:03:24 -03:00
|
|
|
|
|
|
|
rover.failsafe.rc_override_timer = AP_HAL::millis();
|
|
|
|
rover.failsafe_trigger(FAILSAFE_EVENT_RC, false);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
case MAVLINK_MSG_ID_HEARTBEAT:
|
|
|
|
{
|
|
|
|
// We keep track of the last time we received a heartbeat from our GCS for failsafe purposes
|
2016-11-23 13:13:56 -04:00
|
|
|
if (msg->sysid != rover.g.sysid_my_gcs) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2015-11-19 23:04:16 -04:00
|
|
|
rover.last_heartbeat_ms = rover.failsafe.rc_override_timer = AP_HAL::millis();
|
2015-05-12 04:00:25 -03:00
|
|
|
rover.failsafe_trigger(FAILSAFE_EVENT_GCS, false);
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-05-03 11:21:58 -03:00
|
|
|
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET: // MAV ID: 82
|
|
|
|
{
|
|
|
|
// decode packet
|
|
|
|
mavlink_set_attitude_target_t packet;
|
|
|
|
mavlink_msg_set_attitude_target_decode(msg, &packet);
|
|
|
|
|
|
|
|
// exit if vehicle is not in Guided mode
|
2017-07-18 23:19:08 -03:00
|
|
|
if (rover.control_mode != &rover.mode_guided) {
|
2017-05-03 11:21:58 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// ensure type_mask specifies to use thrust
|
|
|
|
if ((packet.type_mask & MAVLINK_SET_ATT_TYPE_MASK_THROTTLE_IGNORE) != 0) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// convert thrust to ground speed
|
2017-08-01 04:07:59 -03:00
|
|
|
packet.thrust = constrain_float(packet.thrust, -1.0f, 1.0f);
|
2017-12-05 21:41:28 -04:00
|
|
|
const float target_speed = rover.control_mode->get_speed_default() * packet.thrust;
|
2017-05-03 11:21:58 -03:00
|
|
|
|
2017-08-01 04:08:33 -03:00
|
|
|
// if the body_yaw_rate field is ignored, convert quaternion to heading
|
2017-05-03 11:21:58 -03:00
|
|
|
if ((packet.type_mask & MAVLINK_SET_ATT_TYPE_MASK_YAW_RATE_IGNORE) != 0) {
|
|
|
|
// convert quaternion to heading
|
2017-08-01 04:08:33 -03:00
|
|
|
float target_heading_cd = degrees(Quaternion(packet.q[0], packet.q[1], packet.q[2], packet.q[3]).get_euler_yaw()) * 100.0f;
|
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_heading_cd, target_speed);
|
2017-05-03 11:21:58 -03:00
|
|
|
} else {
|
2017-08-01 20:10:38 -03:00
|
|
|
// use body_yaw_rate field
|
|
|
|
rover.mode_guided.set_desired_turn_rate_and_speed((RAD_TO_DEG * packet.body_yaw_rate) * 100.0f, target_speed);
|
2017-05-03 11:21:58 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2016-08-23 03:04:30 -03:00
|
|
|
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED: // MAV ID: 84
|
|
|
|
{
|
|
|
|
// decode packet
|
|
|
|
mavlink_set_position_target_local_ned_t packet;
|
|
|
|
mavlink_msg_set_position_target_local_ned_decode(msg, &packet);
|
|
|
|
|
|
|
|
// exit if vehicle is not in Guided mode
|
2017-07-18 23:19:08 -03:00
|
|
|
if (rover.control_mode != &rover.mode_guided) {
|
2016-08-23 03:04:30 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
// check for supported coordinate frames
|
|
|
|
if (packet.coordinate_frame != MAV_FRAME_LOCAL_NED &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_BODY_NED &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_BODY_OFFSET_NED) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
|
2017-05-03 11:21:58 -03:00
|
|
|
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
|
|
|
|
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
|
2017-08-01 07:09:05 -03:00
|
|
|
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
|
|
|
|
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
|
2017-05-03 11:21:58 -03:00
|
|
|
|
2017-08-01 07:09:05 -03:00
|
|
|
// prepare target position
|
2017-05-03 11:21:58 -03:00
|
|
|
Location target_loc = rover.current_loc;
|
2016-08-23 03:04:30 -03:00
|
|
|
if (!pos_ignore) {
|
2016-12-23 05:49:39 -04:00
|
|
|
switch (packet.coordinate_frame) {
|
|
|
|
case MAV_FRAME_BODY_NED:
|
|
|
|
case MAV_FRAME_BODY_OFFSET_NED: {
|
2016-08-23 03:04:30 -03:00
|
|
|
// rotate from body-frame to NE frame
|
2017-05-03 11:06:54 -03:00
|
|
|
const float ne_x = packet.x * rover.ahrs.cos_yaw() - packet.y * rover.ahrs.sin_yaw();
|
|
|
|
const float ne_y = packet.x * rover.ahrs.sin_yaw() + packet.y * rover.ahrs.cos_yaw();
|
2016-08-23 03:04:30 -03:00
|
|
|
// add offset to current location
|
2017-05-03 11:21:58 -03:00
|
|
|
location_offset(target_loc, ne_x, ne_y);
|
2016-12-23 05:49:39 -04:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_FRAME_LOCAL_OFFSET_NED:
|
2016-08-23 03:04:30 -03:00
|
|
|
// add offset to current location
|
2017-05-03 11:21:58 -03:00
|
|
|
location_offset(target_loc, packet.x, packet.y);
|
2016-12-23 05:49:39 -04:00
|
|
|
break;
|
|
|
|
|
|
|
|
default:
|
2016-08-23 03:04:30 -03:00
|
|
|
// MAV_FRAME_LOCAL_NED interpret as an offset from home
|
2017-05-03 11:21:58 -03:00
|
|
|
target_loc = rover.ahrs.get_home();
|
|
|
|
location_offset(target_loc, packet.x, packet.y);
|
2016-12-23 05:49:39 -04:00
|
|
|
break;
|
2016-08-23 03:04:30 -03:00
|
|
|
}
|
2017-05-03 11:21:58 -03:00
|
|
|
}
|
2017-08-01 07:09:05 -03:00
|
|
|
|
2017-05-03 11:21:58 -03:00
|
|
|
float target_speed = 0.0f;
|
2017-08-01 07:09:05 -03:00
|
|
|
float target_yaw_cd = 0.0f;
|
|
|
|
|
|
|
|
// consume velocity and convert to target speed and heading
|
2017-05-03 11:21:58 -03:00
|
|
|
if (!vel_ignore) {
|
2017-12-05 21:41:28 -04:00
|
|
|
const float speed_max = rover.control_mode->get_speed_default();
|
2017-08-01 07:09:05 -03:00
|
|
|
// convert vector length into a speed
|
2017-12-05 21:41:28 -04:00
|
|
|
target_speed = constrain_float(safe_sqrt(sq(packet.vx) + sq(packet.vy)), -speed_max, speed_max);
|
2017-08-01 07:09:05 -03:00
|
|
|
// convert vector direction to target yaw
|
|
|
|
target_yaw_cd = degrees(atan2f(packet.vy, packet.vx)) * 100.0f;
|
2017-10-30 21:00:03 -03:00
|
|
|
|
2017-08-01 07:09:05 -03:00
|
|
|
// rotate target yaw if provided in body-frame
|
2017-05-03 11:21:58 -03:00
|
|
|
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
|
2017-08-01 07:09:05 -03:00
|
|
|
target_yaw_cd = wrap_180_cd(target_yaw_cd + rover.ahrs.yaw_sensor);
|
2017-05-03 11:21:58 -03:00
|
|
|
}
|
2016-08-23 03:04:30 -03:00
|
|
|
}
|
|
|
|
|
2017-12-04 23:12:25 -04:00
|
|
|
// consume yaw heading
|
2017-08-01 07:09:05 -03:00
|
|
|
if (!yaw_ignore) {
|
|
|
|
target_yaw_cd = ToDeg(packet.yaw) * 100.0f;
|
|
|
|
// rotate target yaw if provided in body-frame
|
|
|
|
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
|
|
|
|
target_yaw_cd = wrap_180_cd(target_yaw_cd + rover.ahrs.yaw_sensor);
|
2017-05-03 11:21:58 -03:00
|
|
|
}
|
2017-08-01 07:09:05 -03:00
|
|
|
}
|
2017-12-04 23:12:25 -04:00
|
|
|
// consume yaw rate
|
|
|
|
float target_turn_rate_cds = 0.0f;
|
2017-08-01 07:09:05 -03:00
|
|
|
if (!yaw_rate_ignore) {
|
|
|
|
target_turn_rate_cds = ToDeg(packet.yaw_rate) * 100.0f;
|
|
|
|
}
|
2017-12-04 23:12:25 -04:00
|
|
|
|
|
|
|
// handling case when both velocity and either yaw or yaw-rate are provided
|
2017-10-30 21:00:03 -03:00
|
|
|
// by default, we consider that the rover will drive forward
|
2017-12-04 23:12:25 -04:00
|
|
|
float speed_dir = 1.0f;
|
|
|
|
if (!vel_ignore && (!yaw_ignore || !yaw_rate_ignore)) {
|
|
|
|
// Note: we are using the x-axis velocity to determine direction even though
|
|
|
|
// the frame may have been provided in MAV_FRAME_LOCAL_OFFSET_NED or MAV_FRAME_LOCAL_NED
|
2017-10-30 21:00:03 -03:00
|
|
|
if (is_negative(packet.vx)) {
|
2017-12-04 23:12:25 -04:00
|
|
|
speed_dir = -1.0f;
|
2017-10-30 21:00:03 -03:00
|
|
|
}
|
|
|
|
}
|
2017-08-01 07:09:05 -03:00
|
|
|
|
|
|
|
// set guided mode targets
|
|
|
|
if (!pos_ignore && vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume position target
|
2017-08-01 20:10:38 -03:00
|
|
|
rover.mode_guided.set_desired_location(target_loc);
|
2017-08-01 07:09:05 -03:00
|
|
|
} else if (pos_ignore && !vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume velocity
|
2017-12-04 23:12:25 -04:00
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
2017-10-30 21:00:03 -03:00
|
|
|
} else if (pos_ignore && !vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
|
|
|
// consume velocity and turn rate
|
2017-12-04 23:12:25 -04:00
|
|
|
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, speed_dir * target_speed);
|
2017-10-30 21:00:03 -03:00
|
|
|
} else if (pos_ignore && !vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume velocity
|
2017-12-04 23:12:25 -04:00
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
2017-08-01 07:09:05 -03:00
|
|
|
} else if (pos_ignore && vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume just target heading (probably only skid steering vehicles can do this)
|
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, 0.0f);
|
|
|
|
} else if (pos_ignore && vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
|
|
|
// consume just turn rate(probably only skid steering vehicles can do this)
|
|
|
|
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
|
2017-05-03 11:21:58 -03:00
|
|
|
}
|
2016-08-23 03:04:30 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT: // MAV ID: 86
|
|
|
|
{
|
|
|
|
// decode packet
|
|
|
|
mavlink_set_position_target_global_int_t packet;
|
|
|
|
mavlink_msg_set_position_target_global_int_decode(msg, &packet);
|
|
|
|
|
|
|
|
// exit if vehicle is not in Guided mode
|
2017-07-18 23:19:08 -03:00
|
|
|
if (rover.control_mode != &rover.mode_guided) {
|
2016-08-23 03:04:30 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
// check for supported coordinate frames
|
2017-09-18 23:57:57 -03:00
|
|
|
if (packet.coordinate_frame != MAV_FRAME_GLOBAL &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_INT &&
|
2016-08-23 03:04:30 -03:00
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT &&
|
2017-09-18 23:57:57 -03:00
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT &&
|
2016-08-23 03:04:30 -03:00
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) {
|
|
|
|
break;
|
|
|
|
}
|
2016-11-23 13:13:56 -04:00
|
|
|
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
|
2017-05-03 11:21:58 -03:00
|
|
|
bool vel_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_VEL_IGNORE;
|
|
|
|
bool acc_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_ACC_IGNORE;
|
2017-08-01 07:09:05 -03:00
|
|
|
bool yaw_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_IGNORE;
|
|
|
|
bool yaw_rate_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_YAW_RATE_IGNORE;
|
2017-05-03 11:21:58 -03:00
|
|
|
|
2017-08-01 07:09:05 -03:00
|
|
|
// prepare target position
|
2017-05-03 11:21:58 -03:00
|
|
|
Location target_loc = rover.current_loc;
|
2016-08-23 03:04:30 -03:00
|
|
|
if (!pos_ignore) {
|
2017-05-03 11:21:58 -03:00
|
|
|
// sanity check location
|
|
|
|
if (!check_latlng(packet.lat_int, packet.lon_int)) {
|
|
|
|
// result = MAV_RESULT_FAILED;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
target_loc.lat = packet.lat_int;
|
|
|
|
target_loc.lng = packet.lon_int;
|
|
|
|
}
|
2017-08-01 07:09:05 -03:00
|
|
|
|
2017-05-03 11:21:58 -03:00
|
|
|
float target_speed = 0.0f;
|
2017-08-01 07:09:05 -03:00
|
|
|
float target_yaw_cd = 0.0f;
|
|
|
|
|
|
|
|
// consume velocity and convert to target speed and heading
|
2017-05-03 11:21:58 -03:00
|
|
|
if (!vel_ignore) {
|
2017-12-05 21:41:28 -04:00
|
|
|
const float speed_max = rover.control_mode->get_speed_default();
|
2017-08-01 07:09:05 -03:00
|
|
|
// convert vector length into a speed
|
2017-12-05 21:41:28 -04:00
|
|
|
target_speed = constrain_float(safe_sqrt(sq(packet.vx) + sq(packet.vy)), -speed_max, speed_max);
|
2017-08-01 07:09:05 -03:00
|
|
|
// convert vector direction to target yaw
|
|
|
|
target_yaw_cd = degrees(atan2f(packet.vy, packet.vx)) * 100.0f;
|
2017-10-30 21:00:03 -03:00
|
|
|
|
|
|
|
// rotate target yaw if provided in body-frame
|
|
|
|
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
|
|
|
|
target_yaw_cd = wrap_180_cd(target_yaw_cd + rover.ahrs.yaw_sensor);
|
|
|
|
}
|
2016-08-23 03:04:30 -03:00
|
|
|
}
|
|
|
|
|
2017-12-04 23:12:25 -04:00
|
|
|
// consume yaw heading
|
2017-08-01 07:09:05 -03:00
|
|
|
if (!yaw_ignore) {
|
|
|
|
target_yaw_cd = ToDeg(packet.yaw) * 100.0f;
|
|
|
|
// rotate target yaw if provided in body-frame
|
|
|
|
if (packet.coordinate_frame == MAV_FRAME_BODY_NED || packet.coordinate_frame == MAV_FRAME_BODY_OFFSET_NED) {
|
|
|
|
target_yaw_cd = wrap_180_cd(target_yaw_cd + rover.ahrs.yaw_sensor);
|
2017-05-03 11:21:58 -03:00
|
|
|
}
|
2017-08-01 07:09:05 -03:00
|
|
|
}
|
2017-12-04 23:12:25 -04:00
|
|
|
// consume yaw rate
|
|
|
|
float target_turn_rate_cds = 0.0f;
|
2017-08-01 07:09:05 -03:00
|
|
|
if (!yaw_rate_ignore) {
|
|
|
|
target_turn_rate_cds = ToDeg(packet.yaw_rate) * 100.0f;
|
|
|
|
}
|
2017-12-04 23:12:25 -04:00
|
|
|
|
|
|
|
// handling case when both velocity and either yaw or yaw-rate are provided
|
2017-10-30 21:00:03 -03:00
|
|
|
// by default, we consider that the rover will drive forward
|
2017-12-04 23:12:25 -04:00
|
|
|
float speed_dir = 1.0f;
|
|
|
|
if (!vel_ignore && (!yaw_ignore || !yaw_rate_ignore)) {
|
|
|
|
// Note: we are using the x-axis velocity to determine direction even though
|
|
|
|
// the frame is provided in MAV_FRAME_GLOBAL_xxx
|
2017-10-30 21:00:03 -03:00
|
|
|
if (is_negative(packet.vx)) {
|
2017-12-04 23:12:25 -04:00
|
|
|
speed_dir = -1.0f;
|
2017-10-30 21:00:03 -03:00
|
|
|
}
|
|
|
|
}
|
2017-08-01 07:09:05 -03:00
|
|
|
|
|
|
|
// set guided mode targets
|
|
|
|
if (!pos_ignore && vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume position target
|
2017-08-01 20:10:38 -03:00
|
|
|
rover.mode_guided.set_desired_location(target_loc);
|
2017-08-01 07:09:05 -03:00
|
|
|
} else if (pos_ignore && !vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume velocity
|
2017-12-04 23:12:25 -04:00
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
2017-10-30 21:00:03 -03:00
|
|
|
} else if (pos_ignore && !vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
|
|
|
// consume velocity and turn rate
|
2017-12-04 23:12:25 -04:00
|
|
|
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, speed_dir * target_speed);
|
2017-10-30 21:00:03 -03:00
|
|
|
} else if (pos_ignore && !vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume velocity
|
2017-12-04 23:12:25 -04:00
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
2017-08-01 07:09:05 -03:00
|
|
|
} else if (pos_ignore && vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume just target heading (probably only skid steering vehicles can do this)
|
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, 0.0f);
|
|
|
|
} else if (pos_ignore && vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
|
|
|
// consume just turn rate(probably only skid steering vehicles can do this)
|
|
|
|
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, 0.0f);
|
2017-05-03 11:21:58 -03:00
|
|
|
}
|
2016-08-23 03:04:30 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2012-12-18 16:17:06 -04:00
|
|
|
#if HIL_MODE != HIL_MODE_DISABLED
|
2016-11-23 13:13:56 -04:00
|
|
|
case MAVLINK_MSG_ID_HIL_STATE:
|
|
|
|
{
|
|
|
|
mavlink_hil_state_t packet;
|
|
|
|
mavlink_msg_hil_state_decode(msg, &packet);
|
|
|
|
|
2016-06-01 19:29:32 -03:00
|
|
|
// sanity check location
|
|
|
|
if (!check_latlng(packet.lat, packet.lon)) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
// set gps hil sensor
|
2014-03-30 22:01:54 -03:00
|
|
|
Location loc;
|
|
|
|
loc.lat = packet.lat;
|
|
|
|
loc.lng = packet.lon;
|
|
|
|
loc.alt = packet.alt/10;
|
|
|
|
Vector3f vel(packet.vx, packet.vy, packet.vz);
|
|
|
|
vel *= 0.01f;
|
2016-11-23 13:13:56 -04:00
|
|
|
|
2014-04-01 17:51:15 -03:00
|
|
|
gps.setHIL(0, AP_GPS::GPS_OK_FIX_3D,
|
2014-03-30 22:01:54 -03:00
|
|
|
packet.time_usec/1000,
|
2016-05-04 22:42:16 -03:00
|
|
|
loc, vel, 10, 0);
|
2016-11-23 13:13:56 -04:00
|
|
|
|
|
|
|
// rad/sec
|
2012-04-30 04:17:14 -03:00
|
|
|
Vector3f gyros;
|
2012-12-18 16:17:06 -04:00
|
|
|
gyros.x = packet.rollspeed;
|
|
|
|
gyros.y = packet.pitchspeed;
|
|
|
|
gyros.z = packet.yawspeed;
|
2012-12-18 15:30:42 -04:00
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
// m/s/s
|
|
|
|
Vector3f accels;
|
2013-01-10 14:42:24 -04:00
|
|
|
accels.x = packet.xacc * (GRAVITY_MSS/1000.0f);
|
|
|
|
accels.y = packet.yacc * (GRAVITY_MSS/1000.0f);
|
|
|
|
accels.z = packet.zacc * (GRAVITY_MSS/1000.0f);
|
2016-11-23 13:13:56 -04:00
|
|
|
|
2014-02-22 17:18:15 -04:00
|
|
|
ins.set_gyro(0, gyros);
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2014-02-22 17:18:15 -04:00
|
|
|
ins.set_accel(0, accels);
|
2015-05-15 01:04:51 -03:00
|
|
|
compass.setHIL(0, packet.roll, packet.pitch, packet.yaw);
|
|
|
|
compass.setHIL(1, packet.roll, packet.pitch, packet.yaw);
|
2013-06-03 22:57:59 -03:00
|
|
|
break;
|
2016-11-23 13:13:56 -04:00
|
|
|
}
|
|
|
|
#endif // HIL_MODE
|
2012-04-30 04:17:14 -03:00
|
|
|
|
|
|
|
#if MOUNT == ENABLED
|
2016-11-23 13:13:56 -04:00
|
|
|
// deprecated. Use MAV_CMD_DO_MOUNT_CONFIGURE
|
2012-04-30 04:17:14 -03:00
|
|
|
case MAVLINK_MSG_ID_MOUNT_CONFIGURE:
|
2016-11-23 13:13:56 -04:00
|
|
|
{
|
|
|
|
rover.camera_mount.configure_msg(msg);
|
|
|
|
break;
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2016-11-23 13:13:56 -04:00
|
|
|
// deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
|
2012-04-30 04:17:14 -03:00
|
|
|
case MAVLINK_MSG_ID_MOUNT_CONTROL:
|
2016-11-23 13:13:56 -04:00
|
|
|
{
|
|
|
|
rover.camera_mount.control_msg(msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif // MOUNT == ENABLED
|
2012-05-14 15:33:03 -03:00
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_RADIO:
|
2013-08-24 04:58:37 -03:00
|
|
|
case MAVLINK_MSG_ID_RADIO_STATUS:
|
2012-05-14 15:33:03 -03:00
|
|
|
{
|
2015-05-12 04:00:25 -03:00
|
|
|
handle_radio_status(msg, rover.DataFlash, rover.should_log(MASK_LOG_PM));
|
2012-05-14 15:33:03 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2017-08-16 07:02:56 -03:00
|
|
|
// send or receive fence points with GCS
|
|
|
|
case MAVLINK_MSG_ID_FENCE_POINT: // MAV ID: 160
|
|
|
|
case MAVLINK_MSG_ID_FENCE_FETCH_POINT:
|
|
|
|
rover.g2.fence.handle_msg(*this, msg);
|
|
|
|
break;
|
|
|
|
|
2016-05-04 12:46:01 -03:00
|
|
|
case MAVLINK_MSG_ID_DISTANCE_SENSOR:
|
2017-07-13 08:36:44 -03:00
|
|
|
rover.rangefinder.handle_msg(msg);
|
2017-08-16 07:57:42 -03:00
|
|
|
rover.g2.proximity.handle_msg(msg);
|
2016-05-04 12:46:01 -03:00
|
|
|
break;
|
|
|
|
|
2016-11-06 20:06:37 -04:00
|
|
|
default:
|
|
|
|
handle_common_message(msg);
|
|
|
|
break;
|
2016-11-23 13:13:56 -04:00
|
|
|
} // end switch
|
|
|
|
} // end handle mavlink
|
2012-04-30 04:17:14 -03:00
|
|
|
|
|
|
|
/*
|
2012-12-18 07:44:12 -04:00
|
|
|
* a delay() callback that processes MAVLink packets. We set this as the
|
|
|
|
* callback in long running library initialisation routines to allow
|
|
|
|
* MAVLink to process packets while waiting for the initialisation to
|
|
|
|
* complete
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::mavlink_delay_cb()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2015-05-12 04:00:25 -03:00
|
|
|
static uint32_t last_1hz, last_50hz, last_5s;
|
2017-02-13 07:00:19 -04:00
|
|
|
if (!gcs().chan(0).initialised || in_mavlink_delay) {
|
2016-11-23 13:13:56 -04:00
|
|
|
return;
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
|
|
|
in_mavlink_delay = true;
|
2017-06-14 22:24:33 -03:00
|
|
|
// don't allow potentially expensive logging calls:
|
|
|
|
DataFlash.EnableWrites(false);
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-01-31 06:12:26 -04:00
|
|
|
const uint32_t tnow = millis();
|
2012-12-18 07:44:12 -04:00
|
|
|
if (tnow - last_1hz > 1000) {
|
|
|
|
last_1hz = tnow;
|
2017-07-07 22:16:56 -03:00
|
|
|
gcs().send_message(MSG_HEARTBEAT);
|
|
|
|
gcs().send_message(MSG_EXTENDED_STATUS1);
|
2012-12-18 07:44:12 -04:00
|
|
|
}
|
|
|
|
if (tnow - last_50hz > 20) {
|
|
|
|
last_50hz = tnow;
|
|
|
|
gcs_update();
|
|
|
|
gcs_data_stream_send();
|
2013-08-29 00:14:16 -03:00
|
|
|
notify.update();
|
2012-12-18 07:44:12 -04:00
|
|
|
}
|
|
|
|
if (tnow - last_5s > 5000) {
|
|
|
|
last_5s = tnow;
|
2017-07-08 22:40:59 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Initialising APM");
|
2012-12-18 07:44:12 -04:00
|
|
|
}
|
|
|
|
check_usb_mux();
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2017-06-14 22:24:33 -03:00
|
|
|
DataFlash.EnableWrites(true);
|
2012-04-30 04:17:14 -03:00
|
|
|
in_mavlink_delay = false;
|
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2012-12-18 15:30:42 -04:00
|
|
|
* send data streams in the given rate range on both links
|
2012-04-30 04:17:14 -03:00
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::gcs_data_stream_send(void)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-02-13 07:00:19 -04:00
|
|
|
gcs().data_stream_send();
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
2012-12-18 15:30:42 -04:00
|
|
|
* look for incoming commands on the GCS links
|
2012-04-30 04:17:14 -03:00
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::gcs_update(void)
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-02-13 07:00:19 -04:00
|
|
|
gcs().update();
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2013-10-27 20:33:52 -03:00
|
|
|
/**
|
|
|
|
retry any deferred messages
|
|
|
|
*/
|
2015-05-12 02:03:23 -03:00
|
|
|
void Rover::gcs_retry_deferred(void)
|
2013-10-27 20:33:52 -03:00
|
|
|
{
|
2017-07-18 22:37:04 -03:00
|
|
|
gcs().retry_deferred();
|
2013-10-27 20:33:52 -03:00
|
|
|
}
|
2016-11-21 11:06:25 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
return true if we will accept this packet. Used to implement SYSID_ENFORCE
|
|
|
|
*/
|
|
|
|
bool GCS_MAVLINK_Rover::accept_packet(const mavlink_status_t &status, mavlink_message_t &msg)
|
|
|
|
{
|
2016-11-23 13:13:56 -04:00
|
|
|
if (!rover.g2.sysid_enforce) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
if (msg.msgid == MAVLINK_MSG_ID_RADIO || msg.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return (msg.sysid == rover.g.sysid_my_gcs);
|
|
|
|
}
|
2017-07-08 00:23:03 -03:00
|
|
|
|
2017-07-26 03:12:08 -03:00
|
|
|
AP_Camera *GCS_MAVLINK_Rover::get_camera() const
|
|
|
|
{
|
|
|
|
#if CAMERA == ENABLED
|
|
|
|
return &rover.camera;
|
|
|
|
#else
|
|
|
|
return nullptr;
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2017-07-13 23:49:40 -03:00
|
|
|
AP_ServoRelayEvents *GCS_MAVLINK_Rover::get_servorelayevents() const
|
|
|
|
{
|
|
|
|
return &rover.ServoRelayEvents;
|
|
|
|
}
|
|
|
|
|
2017-07-25 03:36:40 -03:00
|
|
|
AP_AdvancedFailsafe *GCS_MAVLINK_Rover::get_advanced_failsafe() const
|
|
|
|
{
|
|
|
|
#if ADVANCED_FAILSAFE == ENABLED
|
|
|
|
return &rover.g2.afs;
|
|
|
|
#else
|
|
|
|
return nullptr;
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2018-03-07 19:00:43 -04:00
|
|
|
AP_VisualOdom *GCS_MAVLINK_Rover::get_visual_odom() const
|
|
|
|
{
|
|
|
|
#if VISUAL_ODOMETRY_ENABLED == ENABLED
|
|
|
|
return &rover.g2.visual_odom;
|
|
|
|
#else
|
|
|
|
return nullptr;
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2017-07-16 21:47:07 -03:00
|
|
|
Compass *GCS_MAVLINK_Rover::get_compass() const
|
|
|
|
{
|
|
|
|
return &rover.compass;
|
|
|
|
}
|
|
|
|
|
2017-07-08 00:23:03 -03:00
|
|
|
AP_Mission *GCS_MAVLINK_Rover::get_mission()
|
|
|
|
{
|
|
|
|
return &rover.mission;
|
|
|
|
}
|
2017-08-11 02:52:27 -03:00
|
|
|
|
|
|
|
bool GCS_MAVLINK_Rover::set_mode(const uint8_t mode)
|
|
|
|
{
|
2017-12-11 20:38:40 -04:00
|
|
|
Mode *new_mode = rover.mode_from_mode_num((enum mode)mode);
|
2017-08-11 02:52:27 -03:00
|
|
|
if (new_mode == nullptr) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return rover.set_mode(*new_mode, MODE_REASON_GCS_COMMAND);
|
|
|
|
}
|
2017-08-19 06:59:49 -03:00
|
|
|
|
|
|
|
const AP_FWVersion &GCS_MAVLINK_Rover::get_fwver() const
|
|
|
|
{
|
|
|
|
return rover.fwver;
|
|
|
|
}
|
2017-09-18 23:37:09 -03:00
|
|
|
|
|
|
|
void GCS_MAVLINK_Rover::set_ekf_origin(const Location& loc)
|
|
|
|
{
|
|
|
|
rover.set_ekf_origin(loc);
|
|
|
|
}
|