2015-05-13 00:16:45 -03:00
|
|
|
#include "Rover.h"
|
|
|
|
|
2016-05-27 10:04:55 -03:00
|
|
|
#include "GCS_Mavlink.h"
|
|
|
|
|
2022-09-27 22:37:45 -03:00
|
|
|
#include <AP_RPM/AP_RPM_config.h>
|
2019-11-10 22:47:52 -04:00
|
|
|
#include <AP_RangeFinder/AP_RangeFinder_Backend.h>
|
2022-10-21 19:02:20 -03:00
|
|
|
#include <AP_EFI/AP_EFI_config.h>
|
2017-08-08 02:58:52 -03:00
|
|
|
|
2019-02-12 07:55:31 -04:00
|
|
|
MAV_TYPE GCS_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
|
|
|
}
|
|
|
|
|
2019-04-20 20:10:51 -03:00
|
|
|
if (rover.g2.stick_mixing > 0 && rover.control_mode != &rover.mode_initializing) {
|
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
|
|
|
}
|
|
|
|
|
|
|
|
// 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
|
|
|
|
2020-05-23 17:51:49 -03:00
|
|
|
return (MAV_MODE)_base_mode;
|
2018-03-22 06:21:07 -03:00
|
|
|
}
|
|
|
|
|
2019-02-12 07:55:31 -04:00
|
|
|
uint32_t GCS_Rover::custom_mode() const
|
2018-03-22 06:21:07 -03:00
|
|
|
{
|
2023-09-21 12:47:41 -03:00
|
|
|
return (uint32_t)rover.control_mode->mode_number();
|
2018-03-22 06:21:07 -03:00
|
|
|
}
|
|
|
|
|
2019-11-25 22:46:07 -04:00
|
|
|
MAV_STATE GCS_MAVLINK_Rover::vehicle_system_status() const
|
2018-03-22 06:21:07 -03:00
|
|
|
{
|
2018-12-18 06:28:20 -04:00
|
|
|
if ((rover.failsafe.triggered != 0) || rover.failsafe.ekf) {
|
2018-03-22 06:21:07 -03:00
|
|
|
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
|
|
|
}
|
|
|
|
|
2019-05-17 03:53:39 -03:00
|
|
|
void GCS_MAVLINK_Rover::send_position_target_global_int()
|
|
|
|
{
|
|
|
|
Location target;
|
|
|
|
if (!rover.control_mode->get_desired_location(target)) {
|
|
|
|
return;
|
|
|
|
}
|
2021-03-16 14:28:38 -03:00
|
|
|
static constexpr uint16_t POSITION_TARGET_TYPEMASK_LAST_BYTE = 0xF000;
|
|
|
|
static constexpr uint16_t TYPE_MASK = POSITION_TARGET_TYPEMASK_VX_IGNORE | POSITION_TARGET_TYPEMASK_VY_IGNORE | POSITION_TARGET_TYPEMASK_VZ_IGNORE |
|
|
|
|
POSITION_TARGET_TYPEMASK_AX_IGNORE | POSITION_TARGET_TYPEMASK_AY_IGNORE | POSITION_TARGET_TYPEMASK_AZ_IGNORE |
|
2021-07-26 03:43:04 -03:00
|
|
|
POSITION_TARGET_TYPEMASK_YAW_IGNORE | POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE | POSITION_TARGET_TYPEMASK_LAST_BYTE;
|
2019-05-17 03:53:39 -03:00
|
|
|
mavlink_msg_position_target_global_int_send(
|
|
|
|
chan,
|
|
|
|
AP_HAL::millis(), // time_boot_ms
|
2019-07-26 22:38:16 -03:00
|
|
|
MAV_FRAME_GLOBAL, // targets are always global altitude
|
2021-03-16 14:28:38 -03:00
|
|
|
TYPE_MASK, // ignore everything except the x/y/z components
|
2019-05-17 03:53:39 -03:00
|
|
|
target.lat, // latitude as 1e7
|
|
|
|
target.lng, // longitude as 1e7
|
|
|
|
target.alt * 0.01f, // altitude is sent as a float
|
|
|
|
0.0f, // vx
|
|
|
|
0.0f, // vy
|
|
|
|
0.0f, // vz
|
|
|
|
0.0f, // afx
|
|
|
|
0.0f, // afy
|
|
|
|
0.0f, // afz
|
|
|
|
0.0f, // yaw
|
|
|
|
0.0f); // yaw_rate
|
|
|
|
}
|
|
|
|
|
2018-05-04 21:09:34 -03:00
|
|
|
void GCS_MAVLINK_Rover::send_nav_controller_output() const
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2018-05-04 21:09:34 -03:00
|
|
|
if (!rover.control_mode->is_autopilot_mode()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
const Mode *control_mode = rover.control_mode;
|
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
mavlink_msg_nav_controller_output_send(
|
|
|
|
chan,
|
2018-12-11 09:32:14 -04:00
|
|
|
0, // roll
|
2018-05-04 21:09:34 -03:00
|
|
|
degrees(rover.g2.attitude_control.get_desired_pitch()),
|
2018-12-11 10:04:50 -04:00
|
|
|
control_mode->nav_bearing(),
|
|
|
|
control_mode->wp_bearing(),
|
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(),
|
2018-12-11 10:04:50 -04:00
|
|
|
control_mode->crosstrack_error());
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2021-08-24 11:18:45 -03:00
|
|
|
void GCS_MAVLINK_Rover::send_servo_out()
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2017-11-20 19:37:42 -04:00
|
|
|
float motor1, motor3;
|
2021-08-24 11:18:45 -03:00
|
|
|
if (rover.g2.motors.have_skid_steering()) {
|
2017-11-20 19:37:42 -04:00
|
|
|
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,
|
2021-08-24 11:18:45 -03:00
|
|
|
receiver_rssi());
|
2015-02-05 02:23:49 -04:00
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2018-01-30 22:11:27 -04:00
|
|
|
int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const
|
2012-04-30 04:17:14 -03:00
|
|
|
{
|
2018-01-30 22:11:27 -04:00
|
|
|
return rover.g2.motors.get_throttle();
|
2012-04-30 04:17:14 -03:00
|
|
|
}
|
|
|
|
|
2023-10-25 20:05:11 -03:00
|
|
|
#if AP_RANGEFINDER_ENABLED
|
2018-12-18 06:47:19 -04:00
|
|
|
void GCS_MAVLINK_Rover::send_rangefinder() const
|
2013-02-28 21:00:48 -04:00
|
|
|
{
|
2022-05-23 13:53:24 -03:00
|
|
|
float distance = 0;
|
|
|
|
float voltage = 0;
|
2017-08-08 02:58:52 -03:00
|
|
|
bool got_one = false;
|
|
|
|
|
|
|
|
// report smaller distance of all rangefinders
|
2018-12-18 06:47:19 -04:00
|
|
|
for (uint8_t i=0; i<rover.rangefinder.num_sensors(); i++) {
|
|
|
|
AP_RangeFinder_Backend *s = rover.rangefinder.get_backend(i);
|
2017-08-08 02:58:52 -03:00
|
|
|
if (s == nullptr) {
|
|
|
|
continue;
|
2015-04-17 03:41:00 -03:00
|
|
|
}
|
2017-08-08 02:58:52 -03:00
|
|
|
if (!got_one ||
|
2021-10-21 18:42:55 -03:00
|
|
|
s->distance() < distance) {
|
|
|
|
distance = s->distance();
|
2017-08-08 02:58:52 -03:00
|
|
|
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,
|
2021-10-21 18:42:55 -03:00
|
|
|
distance,
|
2013-03-28 21:00:41 -03:00
|
|
|
voltage);
|
2013-02-28 21:00:48 -04:00
|
|
|
}
|
2023-10-25 20:05:11 -03:00
|
|
|
#endif // AP_RANGEFINDER_ENABLED
|
2013-02-28 21:00:48 -04:00
|
|
|
|
2015-06-18 04:37:59 -03:00
|
|
|
/*
|
|
|
|
send PID tuning message
|
|
|
|
*/
|
2019-02-28 19:31:59 -04:00
|
|
|
void GCS_MAVLINK_Rover::send_pid_tuning()
|
2015-06-18 04:37:59 -03:00
|
|
|
{
|
2019-02-28 19:31:59 -04:00
|
|
|
Parameters &g = rover.g;
|
|
|
|
ParametersG2 &g2 = rover.g2;
|
|
|
|
|
2022-03-03 23:29:50 -04:00
|
|
|
const AP_PIDInfo *pid_info;
|
2019-02-28 19:31:59 -04:00
|
|
|
|
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,
|
2019-06-27 06:31:52 -03:00
|
|
|
degrees(pid_info->target),
|
2020-05-17 14:16:36 -03:00
|
|
|
degrees(pid_info->actual),
|
2016-05-29 20:44:23 -03:00
|
|
|
pid_info->FF,
|
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
2021-08-14 00:11:09 -03:00
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
2016-05-29 20:44:23 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2018-08-04 00:24:03 -03:00
|
|
|
|
2018-01-01 02:27:39 -04:00
|
|
|
// speed to throttle PID
|
|
|
|
if (g.gcs_pid_mask & 2) {
|
2022-01-06 06:28:55 -04:00
|
|
|
pid_info = &g2.attitude_control.get_throttle_speed_pid_info();
|
2016-11-23 13:13:56 -04:00
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_ACCZ,
|
2019-06-27 06:31:52 -03:00
|
|
|
pid_info->target,
|
2020-05-17 14:16:36 -03:00
|
|
|
pid_info->actual,
|
|
|
|
pid_info->FF,
|
2016-05-29 20:44:23 -03:00
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
2021-08-14 00:11:09 -03:00
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
2015-06-18 04:37:59 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2018-06-05 05:56:46 -03:00
|
|
|
|
|
|
|
// pitch to throttle pid
|
|
|
|
if (g.gcs_pid_mask & 4) {
|
|
|
|
pid_info = &g2.attitude_control.get_pitch_to_throttle_pid().get_pid_info();
|
|
|
|
mavlink_msg_pid_tuning_send(chan, PID_TUNING_PITCH,
|
2019-06-27 06:31:52 -03:00
|
|
|
degrees(pid_info->target),
|
2020-05-17 14:16:36 -03:00
|
|
|
degrees(pid_info->actual),
|
2018-08-08 01:14:40 -03:00
|
|
|
pid_info->FF,
|
2018-08-08 01:15:07 -03:00
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
2021-08-14 00:11:09 -03:00
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
2018-08-08 01:15:07 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// left wheel rate control pid
|
|
|
|
if (g.gcs_pid_mask & 8) {
|
|
|
|
pid_info = &g2.wheel_rate_control.get_pid(0).get_pid_info();
|
|
|
|
mavlink_msg_pid_tuning_send(chan, 7,
|
2019-06-27 06:31:52 -03:00
|
|
|
pid_info->target,
|
2018-08-08 01:15:07 -03:00
|
|
|
pid_info->actual,
|
|
|
|
pid_info->FF,
|
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
2021-08-14 00:11:09 -03:00
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
2018-08-08 01:15:07 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// right wheel rate control pid
|
|
|
|
if (g.gcs_pid_mask & 16) {
|
|
|
|
pid_info = &g2.wheel_rate_control.get_pid(1).get_pid_info();
|
|
|
|
mavlink_msg_pid_tuning_send(chan, 8,
|
2019-06-27 06:31:52 -03:00
|
|
|
pid_info->target,
|
2018-08-08 01:15:07 -03:00
|
|
|
pid_info->actual,
|
|
|
|
pid_info->FF,
|
2018-06-05 05:56:46 -03:00
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
2021-08-14 00:11:09 -03:00
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
2018-06-05 05:56:46 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2018-09-25 10:09:47 -03:00
|
|
|
|
|
|
|
// sailboat heel to mainsail pid
|
|
|
|
if (g.gcs_pid_mask & 32) {
|
|
|
|
pid_info = &g2.attitude_control.get_sailboat_heel_pid().get_pid_info();
|
|
|
|
mavlink_msg_pid_tuning_send(chan, 9,
|
2019-06-27 06:31:52 -03:00
|
|
|
pid_info->target,
|
2018-09-25 10:09:47 -03:00
|
|
|
pid_info->actual,
|
|
|
|
pid_info->FF,
|
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
2021-08-14 00:11:09 -03:00
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
2018-09-25 10:09:47 -03:00
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2021-11-26 00:02:20 -04:00
|
|
|
|
|
|
|
// Position Controller Velocity North PID
|
|
|
|
if (g.gcs_pid_mask & 64) {
|
|
|
|
pid_info = &g2.pos_control.get_vel_pid().get_pid_info_x();
|
|
|
|
mavlink_msg_pid_tuning_send(chan, 10,
|
|
|
|
pid_info->target,
|
|
|
|
pid_info->actual,
|
|
|
|
pid_info->FF,
|
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// Position Controller Velocity East PID
|
|
|
|
if (g.gcs_pid_mask & 128) {
|
|
|
|
pid_info = &g2.pos_control.get_vel_pid().get_pid_info_y();
|
|
|
|
mavlink_msg_pid_tuning_send(chan, 11,
|
|
|
|
pid_info->target,
|
|
|
|
pid_info->actual,
|
|
|
|
pid_info->FF,
|
|
|
|
pid_info->P,
|
|
|
|
pid_info->I,
|
|
|
|
pid_info->D,
|
|
|
|
pid_info->slew_rate,
|
|
|
|
pid_info->Dmod);
|
|
|
|
if (!HAVE_PAYLOAD_SPACE(chan, PID_TUNING)) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
}
|
2015-06-18 04:37:59 -03:00
|
|
|
}
|
|
|
|
|
2019-04-30 07:22:50 -03:00
|
|
|
void Rover::send_wheel_encoder_distance(const mavlink_channel_t chan)
|
2019-01-25 22:14:00 -04:00
|
|
|
{
|
|
|
|
// send wheel encoder data using wheel_distance message
|
|
|
|
if (g2.wheel_encoder.num_sensors() > 0) {
|
2019-01-28 06:06:50 -04:00
|
|
|
double distances[MAVLINK_MSG_WHEEL_DISTANCE_FIELD_DISTANCE_LEN] {};
|
2019-01-25 22:14:00 -04:00
|
|
|
for (uint8_t i = 0; i < g2.wheel_encoder.num_sensors(); i++) {
|
|
|
|
distances[i] = wheel_encoder_last_distance_m[i];
|
|
|
|
}
|
2019-10-17 08:03:18 -03:00
|
|
|
mavlink_msg_wheel_distance_send(chan, 1000UL * AP_HAL::millis(), g2.wheel_encoder.num_sensors(), distances);
|
2019-01-25 22:14:00 -04:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2017-07-12 04:42:48 -03:00
|
|
|
uint8_t GCS_MAVLINK_Rover::sysid_my_gcs() const
|
|
|
|
{
|
|
|
|
return rover.g.sysid_my_gcs;
|
|
|
|
}
|
2020-05-23 17:51:49 -03:00
|
|
|
|
2018-12-13 19:12:34 -04:00
|
|
|
bool GCS_MAVLINK_Rover::sysid_enforce() const
|
|
|
|
{
|
|
|
|
return rover.g2.sysid_enforce;
|
|
|
|
}
|
2017-07-12 04:42:48 -03:00
|
|
|
|
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
|
|
|
}
|
|
|
|
|
2019-03-01 07:50:14 -04:00
|
|
|
bool GCS_Rover::vehicle_initialised() const
|
2018-12-17 22:07:15 -04:00
|
|
|
{
|
|
|
|
return rover.control_mode != &rover.mode_initializing;
|
|
|
|
}
|
|
|
|
|
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
|
|
|
{
|
|
|
|
switch (id) {
|
|
|
|
|
|
|
|
case MSG_SERVO_OUT:
|
|
|
|
CHECK_PAYLOAD_SIZE(RC_CHANNELS_SCALED);
|
2021-08-24 11:18:45 -03:00
|
|
|
send_servo_out();
|
2012-04-30 04:17:14 -03:00
|
|
|
break;
|
|
|
|
|
2019-01-25 22:14:00 -04:00
|
|
|
case MSG_WHEEL_DISTANCE:
|
|
|
|
CHECK_PAYLOAD_SIZE(WHEEL_DISTANCE);
|
|
|
|
rover.send_wheel_encoder_distance(chan);
|
|
|
|
break;
|
|
|
|
|
2018-09-25 10:09:47 -03:00
|
|
|
case MSG_WIND:
|
|
|
|
CHECK_PAYLOAD_SIZE(WIND);
|
2018-11-01 02:27:25 -03:00
|
|
|
rover.g2.windvane.send_wind(chan);
|
2015-01-06 00:17:56 -04:00
|
|
|
break;
|
2015-01-06 00:28:38 -04:00
|
|
|
|
2019-07-20 03:24:56 -03:00
|
|
|
case MSG_ADSB_VEHICLE: {
|
|
|
|
AP_OADatabase *oadb = AP::oadatabase();
|
|
|
|
if (oadb != nullptr) {
|
|
|
|
CHECK_PAYLOAD_SIZE(ADSB_VEHICLE);
|
|
|
|
uint16_t interval_ms = 0;
|
|
|
|
if (get_ap_message_interval(id, interval_ms)) {
|
|
|
|
oadb->send_adsb_vehicle(chan, interval_ms);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
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;
|
|
|
|
}
|
|
|
|
|
2019-04-30 07:22:50 -03:00
|
|
|
void GCS_MAVLINK_Rover::packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg)
|
2018-07-07 02:12:45 -03:00
|
|
|
{
|
2023-08-11 09:28:32 -03:00
|
|
|
#if AP_FOLLOW_ENABLED
|
2018-07-07 02:12:45 -03:00
|
|
|
// pass message to follow library
|
|
|
|
rover.g2.follow.handle_msg(msg);
|
2023-08-11 09:28:32 -03:00
|
|
|
#endif
|
2018-07-07 02:12:45 -03:00
|
|
|
GCS_MAVLINK::packetReceived(status, msg);
|
|
|
|
}
|
|
|
|
|
2013-10-20 19:32:39 -03:00
|
|
|
/*
|
|
|
|
default stream rates to 1Hz
|
|
|
|
*/
|
2019-06-19 08:26:19 -03:00
|
|
|
const AP_Param::GroupInfo GCS_MAVLINK_Parameters::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
|
2022-10-16 20:00:46 -03:00
|
|
|
// @Description: MAVLink Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, and SCALED_PRESSURE3
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2021-02-19 11:33:15 -04:00
|
|
|
// @Range: 0 50
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2013-09-11 20:51:36 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("RAW_SENS", 0, GCS_MAVLINK_Parameters, streamRates[0], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: EXT_STAT
|
2022-10-16 20:00:46 -03:00
|
|
|
// @DisplayName: Extended status stream rate
|
|
|
|
// @Description: MAVLink Stream rate of SYS_STATUS, POWER_STATUS, MCU_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW_INT (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, FENCE_STATUS, and GLOBAL_TARGET_POS_INT
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2021-02-19 11:33:15 -04:00
|
|
|
// @Range: 0 50
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2013-09-11 20:51:36 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("EXT_STAT", 1, GCS_MAVLINK_Parameters, streamRates[1], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: RC_CHAN
|
2022-10-16 20:00:46 -03:00
|
|
|
// @DisplayName: RC Channel stream rate
|
|
|
|
// @Description: MAVLink Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2021-02-19 11:33:15 -04:00
|
|
|
// @Range: 0 50
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2013-09-11 20:51:36 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("RC_CHAN", 2, GCS_MAVLINK_Parameters, streamRates[2], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: RAW_CTRL
|
2022-10-16 20:00:46 -03:00
|
|
|
// @DisplayName: Raw Control stream rate
|
|
|
|
// @Description: MAVLink Raw Control stream rate of SERVO_OUT
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2021-02-19 11:33:15 -04:00
|
|
|
// @Range: 0 50
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2013-09-11 20:51:36 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("RAW_CTRL", 3, GCS_MAVLINK_Parameters, streamRates[3], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: POSITION
|
2022-10-16 20:00:46 -03:00
|
|
|
// @DisplayName: Position stream rate
|
|
|
|
// @Description: MAVLink Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2021-02-19 11:33:15 -04:00
|
|
|
// @Range: 0 50
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2013-09-11 20:51:36 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("POSITION", 4, GCS_MAVLINK_Parameters, 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
|
2022-10-16 20:00:46 -03:00
|
|
|
// @Description: MAVLink Stream rate of ATTITUDE, SIMSTATE (SIM only), AHRS2 and PID_TUNING
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2021-02-19 11:33:15 -04:00
|
|
|
// @Range: 0 50
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2013-09-11 20:51:36 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("EXTRA1", 5, GCS_MAVLINK_Parameters, streamRates[5], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: EXTRA2
|
2022-10-16 20:00:46 -03:00
|
|
|
// @DisplayName: Extra data type 2 stream rate
|
|
|
|
// @Description: MAVLink Stream rate of VFR_HUD
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2021-02-19 11:33:15 -04:00
|
|
|
// @Range: 0 50
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2013-09-11 20:51:36 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("EXTRA2", 6, GCS_MAVLINK_Parameters, streamRates[6], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: EXTRA3
|
2022-10-16 20:00:46 -03:00
|
|
|
// @DisplayName: Extra data type 3 stream rate
|
|
|
|
// @Description: MAVLink Stream rate of AHRS, SYSTEM_TIME, WIND, RANGEFINDER, DISTANCE_SENSOR, BATTERY2, BATTERY_STATUS, GIMBAL_DEVICE_ATTITUDE_STATUS, OPTICAL_FLOW, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION, RPM, ESC TELEMETRY, and WHEEL_DISTANCE
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2021-02-19 11:33:15 -04:00
|
|
|
// @Range: 0 50
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2013-09-11 20:51:36 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("EXTRA3", 7, GCS_MAVLINK_Parameters, streamRates[7], 1),
|
2013-09-11 20:51:36 -03:00
|
|
|
|
|
|
|
// @Param: PARAMS
|
2022-10-16 20:00:46 -03:00
|
|
|
// @DisplayName: Parameter stream rate
|
|
|
|
// @Description: MAVLink Stream rate of PARAM_VALUE
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Units: Hz
|
2021-02-19 11:33:15 -04:00
|
|
|
// @Range: 0 50
|
2013-09-11 20:51:36 -03:00
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2013-09-11 20:51:36 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("PARAMS", 8, GCS_MAVLINK_Parameters, streamRates[8], 10),
|
2019-07-20 03:24:56 -03:00
|
|
|
|
|
|
|
// @Param: ADSB
|
2022-10-16 20:00:46 -03:00
|
|
|
// @DisplayName: ADSB stream rate
|
|
|
|
// @Description: MAVLink ADSB (AIS) stream rate
|
2019-07-20 03:24:56 -03:00
|
|
|
// @Units: Hz
|
|
|
|
// @Range: 0 50
|
|
|
|
// @Increment: 1
|
2022-02-19 21:08:12 -04:00
|
|
|
// @RebootRequired: True
|
2019-07-20 03:24:56 -03:00
|
|
|
// @User: Advanced
|
2019-06-19 08:26:19 -03:00
|
|
|
AP_GROUPINFO("ADSB", 9, GCS_MAVLINK_Parameters, streamRates[9], 0),
|
2019-07-20 03:24:56 -03:00
|
|
|
|
2012-04-30 04:17:14 -03:00
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
2018-05-21 01:06:33 -03:00
|
|
|
static const ap_message STREAM_RAW_SENSORS_msgs[] = {
|
2018-12-04 20:36:50 -04:00
|
|
|
MSG_RAW_IMU,
|
|
|
|
MSG_SCALED_IMU2,
|
|
|
|
MSG_SCALED_IMU3,
|
2018-12-07 02:29:16 -04:00
|
|
|
MSG_SCALED_PRESSURE,
|
|
|
|
MSG_SCALED_PRESSURE2,
|
|
|
|
MSG_SCALED_PRESSURE3,
|
2017-08-21 02:53:37 -03:00
|
|
|
};
|
2018-05-21 01:06:33 -03:00
|
|
|
static const ap_message STREAM_EXTENDED_STATUS_msgs[] = {
|
2018-12-17 22:07:15 -04:00
|
|
|
MSG_SYS_STATUS,
|
|
|
|
MSG_POWER_STATUS,
|
2023-10-27 04:16:35 -03:00
|
|
|
#if HAL_WITH_MCU_MONITORING
|
2021-08-23 01:56:22 -03:00
|
|
|
MSG_MCU_STATUS,
|
2023-10-27 04:16:35 -03:00
|
|
|
#endif
|
2018-12-04 01:18:21 -04:00
|
|
|
MSG_MEMINFO,
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_CURRENT_WAYPOINT,
|
|
|
|
MSG_GPS_RAW,
|
|
|
|
MSG_GPS_RTK,
|
2023-10-25 01:24:00 -03:00
|
|
|
#if GPS_MAX_RECEIVERS > 1
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_GPS2_RAW,
|
|
|
|
MSG_GPS2_RTK,
|
2023-10-25 01:24:00 -03:00
|
|
|
#endif
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_NAV_CONTROLLER_OUTPUT,
|
2023-10-03 06:49:35 -03:00
|
|
|
#if AP_FENCE_ENABLED
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_FENCE_STATUS,
|
2023-10-03 06:49:35 -03:00
|
|
|
#endif
|
2019-05-17 03:53:39 -03:00
|
|
|
MSG_POSITION_TARGET_GLOBAL_INT,
|
2017-08-21 02:53:37 -03:00
|
|
|
};
|
2018-05-21 01:06:33 -03:00
|
|
|
static const ap_message STREAM_POSITION_msgs[] = {
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_LOCATION,
|
|
|
|
MSG_LOCAL_POSITION
|
|
|
|
};
|
2018-05-21 01:06:33 -03:00
|
|
|
static const ap_message STREAM_RAW_CONTROLLER_msgs[] = {
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_SERVO_OUT,
|
|
|
|
};
|
2018-05-21 01:06:33 -03:00
|
|
|
static const ap_message STREAM_RC_CHANNELS_msgs[] = {
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_SERVO_OUTPUT_RAW,
|
2019-07-06 20:00:53 -03:00
|
|
|
MSG_RC_CHANNELS,
|
|
|
|
MSG_RC_CHANNELS_RAW, // only sent on a mavlink1 connection
|
2017-08-21 02:53:37 -03:00
|
|
|
};
|
2018-05-21 01:06:33 -03:00
|
|
|
static const ap_message STREAM_EXTRA1_msgs[] = {
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_ATTITUDE,
|
2023-11-18 20:38:47 -04:00
|
|
|
#if AP_SIM_ENABLED
|
2018-12-18 16:22:59 -04:00
|
|
|
MSG_SIMSTATE,
|
2023-11-18 20:38:47 -04:00
|
|
|
#endif
|
2018-12-18 16:22:59 -04:00
|
|
|
MSG_AHRS2,
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_PID_TUNING,
|
|
|
|
};
|
2018-05-21 01:06:33 -03:00
|
|
|
static const ap_message STREAM_EXTRA2_msgs[] = {
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_VFR_HUD
|
|
|
|
};
|
2018-05-21 01:06:33 -03:00
|
|
|
static const ap_message STREAM_EXTRA3_msgs[] = {
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_AHRS,
|
2018-09-25 10:09:47 -03:00
|
|
|
MSG_WIND,
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_RANGEFINDER,
|
2018-12-18 06:47:19 -04:00
|
|
|
MSG_DISTANCE_SENSOR,
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_SYSTEM_TIME,
|
2023-10-24 22:15:02 -03:00
|
|
|
#if AP_BATTERY_ENABLED
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_BATTERY_STATUS,
|
2023-10-24 22:15:02 -03:00
|
|
|
#endif
|
2023-10-27 04:10:37 -03:00
|
|
|
#if HAL_MOUNT_ENABLED
|
2022-07-11 05:08:53 -03:00
|
|
|
MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,
|
2023-10-27 04:10:37 -03:00
|
|
|
#endif
|
2023-10-27 04:13:08 -03:00
|
|
|
#if AP_OPTICALFLOW_ENABLED
|
2022-09-07 03:49:51 -03:00
|
|
|
MSG_OPTICAL_FLOW,
|
2023-10-27 04:13:08 -03:00
|
|
|
#endif
|
2023-09-20 09:58:20 -03:00
|
|
|
#if COMPASS_CAL_ENABLED
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_MAG_CAL_REPORT,
|
|
|
|
MSG_MAG_CAL_PROGRESS,
|
2023-09-20 09:58:20 -03:00
|
|
|
#endif
|
2017-08-21 02:53:37 -03:00
|
|
|
MSG_EKF_STATUS_REPORT,
|
|
|
|
MSG_VIBRATION,
|
2022-09-27 22:37:45 -03:00
|
|
|
#if AP_RPM_ENABLED
|
2018-06-20 20:51:06 -03:00
|
|
|
MSG_RPM,
|
2022-09-27 22:37:45 -03:00
|
|
|
#endif
|
2019-01-25 22:14:00 -04:00
|
|
|
MSG_WHEEL_DISTANCE,
|
2023-10-27 04:24:38 -03:00
|
|
|
#if HAL_WITH_ESC_TELEM
|
2018-06-20 20:51:06 -03:00
|
|
|
MSG_ESC_TELEMETRY,
|
2023-10-27 04:24:38 -03:00
|
|
|
#endif
|
2022-10-21 19:02:20 -03:00
|
|
|
#if HAL_EFI_ENABLED
|
|
|
|
MSG_EFI_STATUS,
|
|
|
|
#endif
|
2017-08-21 02:53:37 -03:00
|
|
|
};
|
2018-05-22 22:23:12 -03:00
|
|
|
static const ap_message STREAM_PARAMS_msgs[] = {
|
|
|
|
MSG_NEXT_PARAM
|
|
|
|
};
|
2019-07-20 03:24:56 -03:00
|
|
|
static const ap_message STREAM_ADSB_msgs[] = {
|
2020-03-17 17:57:23 -03:00
|
|
|
MSG_ADSB_VEHICLE,
|
2023-10-24 22:42:16 -03:00
|
|
|
#if AP_AIS_ENABLED
|
2020-03-17 17:57:23 -03:00
|
|
|
MSG_AIS_VESSEL,
|
2023-10-24 22:42:16 -03:00
|
|
|
#endif
|
2019-07-20 03:24:56 -03:00
|
|
|
};
|
2012-12-18 15:30:42 -04:00
|
|
|
|
2017-08-21 02:53:37 -03:00
|
|
|
const struct GCS_MAVLINK::stream_entries GCS_MAVLINK::all_stream_entries[] = {
|
|
|
|
MAV_STREAM_ENTRY(STREAM_RAW_SENSORS),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_EXTENDED_STATUS),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_POSITION),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_RAW_CONTROLLER),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_RC_CHANNELS),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_EXTRA1),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_EXTRA2),
|
|
|
|
MAV_STREAM_ENTRY(STREAM_EXTRA3),
|
2019-07-20 03:24:56 -03:00
|
|
|
MAV_STREAM_ENTRY(STREAM_ADSB),
|
2018-05-22 22:23:12 -03:00
|
|
|
MAV_STREAM_ENTRY(STREAM_PARAMS),
|
2017-08-21 02:53:37 -03:00
|
|
|
MAV_STREAM_TERMINATOR // must have this at end of stream_entries
|
|
|
|
};
|
2013-10-27 20:33:52 -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
|
|
|
{
|
2019-03-08 01:41:50 -04:00
|
|
|
if (!rover.control_mode->in_guided_mode()) {
|
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)
|
2019-05-08 21:54:40 -03:00
|
|
|
return rover.mode_guided.set_desired_location(cmd.content.location);
|
2014-03-18 20:06:58 -03:00
|
|
|
}
|
|
|
|
|
2023-09-07 07:13:30 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
|
2018-03-17 05:19:30 -03:00
|
|
|
{
|
2023-09-07 07:13:30 -03:00
|
|
|
if (packet.y == 1) {
|
2019-05-13 16:10:22 -03:00
|
|
|
if (rover.g2.windvane.start_direction_calibration()) {
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
} else {
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
2023-09-07 07:13:30 -03:00
|
|
|
} else if (packet.y == 2) {
|
2019-05-13 16:10:22 -03:00
|
|
|
if (rover.g2.windvane.start_speed_calibration()) {
|
2018-09-26 22:41:26 -03:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
} else {
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
2018-03-17 05:19:30 -03:00
|
|
|
}
|
|
|
|
|
2022-12-08 02:47:13 -04:00
|
|
|
return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);
|
2018-03-17 05:19:30 -03:00
|
|
|
}
|
|
|
|
|
2019-09-12 06:51:06 -03:00
|
|
|
bool GCS_MAVLINK_Rover::set_home_to_current_location(bool _lock) {
|
|
|
|
return rover.set_home_to_current_location(_lock);
|
2018-07-05 22:34:29 -03:00
|
|
|
}
|
2020-05-23 17:51:49 -03:00
|
|
|
|
2019-09-12 06:51:06 -03:00
|
|
|
bool GCS_MAVLINK_Rover::set_home(const Location& loc, bool _lock) {
|
|
|
|
return rover.set_home(loc, _lock);
|
2018-07-05 22:34:29 -03:00
|
|
|
}
|
|
|
|
|
2023-08-17 04:53:03 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
|
2018-07-03 23:38:22 -03:00
|
|
|
{
|
|
|
|
switch (packet.command) {
|
|
|
|
|
|
|
|
case MAV_CMD_DO_CHANGE_SPEED:
|
|
|
|
// param1 : unused
|
|
|
|
// param2 : new speed in m/s
|
|
|
|
if (!rover.control_mode->set_desired_speed(packet.param2)) {
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
|
2020-09-07 09:17:50 -03:00
|
|
|
case MAV_CMD_DO_REPOSITION:
|
|
|
|
return handle_command_int_do_reposition(packet);
|
|
|
|
|
2018-08-22 01:46:35 -03:00
|
|
|
case MAV_CMD_DO_SET_REVERSE:
|
|
|
|
// param1 : Direction (0=Forward, 1=Reverse)
|
|
|
|
rover.control_mode->set_reversed(is_equal(packet.param1,1.0f));
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
|
2023-08-23 04:38:07 -03:00
|
|
|
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
|
|
|
|
if (rover.set_mode(rover.mode_rtl, ModeReason::GCS_COMMAND)) {
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
|
2023-08-23 23:19:44 -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)
|
|
|
|
return rover.mavlink_motor_test_start(*this,
|
|
|
|
(AP_MotorsUGV::motor_test_order)packet.param1,
|
|
|
|
static_cast<uint8_t>(packet.param2),
|
|
|
|
static_cast<int16_t>(packet.param3),
|
|
|
|
packet.param4);
|
|
|
|
|
2023-08-24 09:31:48 -03:00
|
|
|
case MAV_CMD_MISSION_START:
|
|
|
|
if (rover.set_mode(rover.mode_auto, ModeReason::GCS_COMMAND)) {
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
|
2023-08-25 21:37:19 -03:00
|
|
|
#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED
|
2023-08-24 21:15:32 -03:00
|
|
|
case MAV_CMD_NAV_SET_YAW_SPEED:
|
2023-08-25 21:37:19 -03:00
|
|
|
send_received_message_deprecation_warning("MAV_CMD_NAV_SET_YAW_SPEED");
|
2023-08-24 21:15:32 -03:00
|
|
|
return handle_command_nav_set_yaw_speed(packet, msg);
|
2023-08-25 21:37:19 -03:00
|
|
|
#endif
|
2023-08-24 21:15:32 -03:00
|
|
|
|
2018-07-03 23:38:22 -03:00
|
|
|
default:
|
2023-08-17 04:53:03 -03:00
|
|
|
return GCS_MAVLINK::handle_command_int_packet(packet, msg);
|
2018-07-03 23:38:22 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2023-08-25 21:37:19 -03:00
|
|
|
#if AP_MAVLINK_MAV_CMD_NAV_SET_YAW_SPEED_ENABLED
|
2023-08-24 21:15:32 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK_Rover::handle_command_nav_set_yaw_speed(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
|
2018-07-03 23:32:04 -03:00
|
|
|
{
|
2023-08-24 22:00:21 -03:00
|
|
|
// param1 : yaw angle (may be absolute or relative)
|
|
|
|
// param2 : Speed - in metres/second
|
|
|
|
// param3 : 0 = param1 is absolute, 1 = param1 is relative
|
2018-07-03 23:32:04 -03:00
|
|
|
|
|
|
|
// exit if vehicle is not in Guided mode
|
2019-03-08 01:41:50 -04:00
|
|
|
if (!rover.control_mode->in_guided_mode()) {
|
2018-11-12 02:26:38 -04:00
|
|
|
return MAV_RESULT_FAILED;
|
2018-07-03 23:32:04 -03:00
|
|
|
}
|
|
|
|
|
2019-11-04 23:07:24 -04:00
|
|
|
// get final angle, 1 = Relative, 0 = Absolute
|
|
|
|
if (packet.param3 > 0) {
|
|
|
|
// relative angle
|
|
|
|
rover.mode_guided.set_desired_heading_delta_and_speed(packet.param1 * 100.0f, packet.param2);
|
|
|
|
} else {
|
|
|
|
// absolute angle
|
|
|
|
rover.mode_guided.set_desired_heading_and_speed(packet.param1 * 100.0f, packet.param2);
|
|
|
|
}
|
2018-07-03 23:32:04 -03:00
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
2023-08-25 21:37:19 -03:00
|
|
|
#endif
|
2018-07-03 23:32:04 -03:00
|
|
|
|
2020-09-07 09:17:50 -03:00
|
|
|
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
|
|
|
|
{
|
|
|
|
const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
|
|
|
|
if (!rover.control_mode->in_guided_mode() && !change_modes) {
|
|
|
|
return MAV_RESULT_DENIED;
|
|
|
|
}
|
|
|
|
|
|
|
|
// sanity check location
|
|
|
|
if (!check_latlng(packet.x, packet.y)) {
|
|
|
|
return MAV_RESULT_DENIED;
|
|
|
|
}
|
|
|
|
if (packet.x == 0 && packet.y == 0) {
|
|
|
|
return MAV_RESULT_DENIED;
|
|
|
|
}
|
|
|
|
|
2022-02-02 23:58:21 -04:00
|
|
|
Location requested_location {};
|
|
|
|
if (!location_from_command_t(packet, requested_location)) {
|
2020-09-07 09:17:50 -03:00
|
|
|
return MAV_RESULT_DENIED;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!rover.control_mode->in_guided_mode()) {
|
|
|
|
if (!rover.set_mode(Mode::Number::GUIDED, ModeReason::GCS_COMMAND)) {
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-10-05 20:54:38 -03:00
|
|
|
if (is_positive(packet.param1)) {
|
|
|
|
if (!rover.control_mode->set_desired_speed(packet.param1)) {
|
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-09-07 09:17:50 -03:00
|
|
|
// set the destination
|
2022-02-02 23:58:21 -04:00
|
|
|
if (!rover.mode_guided.set_desired_location(requested_location)) {
|
2020-09-07 09:17:50 -03:00
|
|
|
return MAV_RESULT_FAILED;
|
|
|
|
}
|
|
|
|
|
|
|
|
return MAV_RESULT_ACCEPTED;
|
|
|
|
}
|
|
|
|
|
2019-04-30 07:22:50 -03:00
|
|
|
void GCS_MAVLINK_Rover::handleMessage(const mavlink_message_t &msg)
|
2014-03-18 20:06:58 -03:00
|
|
|
{
|
2019-04-30 07:22:50 -03:00
|
|
|
switch (msg.msgid) {
|
2021-01-04 00:46:45 -04:00
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_SET_ATTITUDE_TARGET:
|
|
|
|
handle_set_attitude_target(msg);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
|
|
|
|
handle_set_position_target_local_ned(msg);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
|
|
|
|
handle_set_position_target_global_int(msg);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAVLINK_MSG_ID_RADIO:
|
|
|
|
case MAVLINK_MSG_ID_RADIO_STATUS:
|
|
|
|
handle_radio(msg);
|
|
|
|
break;
|
|
|
|
|
|
|
|
default:
|
|
|
|
handle_common_message(msg);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2022-11-21 23:40:31 -04:00
|
|
|
void GCS_MAVLINK_Rover::handle_manual_control_axes(const mavlink_manual_control_t &packet, const uint32_t tnow)
|
2021-01-04 05:23:55 -04:00
|
|
|
{
|
|
|
|
manual_override(rover.channel_steer, packet.y, 1000, 2000, tnow);
|
|
|
|
manual_override(rover.channel_throttle, packet.z, 1000, 2000, tnow);
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2021-01-04 00:46:45 -04:00
|
|
|
void GCS_MAVLINK_Rover::handle_set_attitude_target(const mavlink_message_t &msg)
|
2021-01-04 05:23:55 -04:00
|
|
|
{
|
|
|
|
// decode packet
|
|
|
|
mavlink_set_attitude_target_t packet;
|
|
|
|
mavlink_msg_set_attitude_target_decode(&msg, &packet);
|
2017-05-03 11:21:58 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
// exit if vehicle is not in Guided mode
|
|
|
|
if (!rover.control_mode->in_guided_mode()) {
|
|
|
|
return;
|
|
|
|
}
|
2017-05-03 11:21:58 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
// ensure type_mask specifies to use thrust
|
|
|
|
if ((packet.type_mask & MAVLINK_SET_ATT_TYPE_MASK_THROTTLE_IGNORE) != 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// convert thrust to ground speed
|
|
|
|
packet.thrust = constrain_float(packet.thrust, -1.0f, 1.0f);
|
|
|
|
const float target_speed = rover.control_mode->get_speed_default() * packet.thrust;
|
|
|
|
|
|
|
|
// if the body_yaw_rate field is ignored, convert quaternion to heading
|
|
|
|
if ((packet.type_mask & MAVLINK_SET_ATT_TYPE_MASK_YAW_RATE_IGNORE) != 0) {
|
|
|
|
// convert quaternion to heading
|
|
|
|
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);
|
|
|
|
} else {
|
|
|
|
// 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
|
|
|
|
2021-01-04 00:46:45 -04:00
|
|
|
void GCS_MAVLINK_Rover::handle_set_position_target_local_ned(const mavlink_message_t &msg)
|
2021-01-04 05:23:55 -04:00
|
|
|
{
|
|
|
|
// decode packet
|
|
|
|
mavlink_set_position_target_local_ned_t packet;
|
|
|
|
mavlink_msg_set_position_target_local_ned_decode(&msg, &packet);
|
2016-08-23 03:04:30 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
// exit if vehicle is not in Guided mode
|
|
|
|
if (!rover.control_mode->in_guided_mode()) {
|
|
|
|
return;
|
|
|
|
}
|
2020-08-26 23:20:10 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
// need ekf origin
|
|
|
|
Location ekf_origin;
|
|
|
|
if (!rover.ahrs.get_origin(ekf_origin)) {
|
|
|
|
return;
|
|
|
|
}
|
2016-08-23 03:04:30 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
// 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) {
|
|
|
|
return;
|
|
|
|
}
|
2017-08-01 07:09:05 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
|
|
|
|
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;
|
|
|
|
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;
|
|
|
|
|
|
|
|
// prepare target position
|
|
|
|
Location target_loc = rover.current_loc;
|
|
|
|
if (!pos_ignore) {
|
|
|
|
switch (packet.coordinate_frame) {
|
|
|
|
case MAV_FRAME_BODY_NED:
|
|
|
|
case MAV_FRAME_BODY_OFFSET_NED: {
|
|
|
|
// rotate from body-frame to NE frame
|
|
|
|
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();
|
|
|
|
// add offset to current location
|
|
|
|
target_loc.offset(ne_x, ne_y);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_FRAME_LOCAL_OFFSET_NED:
|
|
|
|
// add offset to current location
|
|
|
|
target_loc.offset(packet.x, packet.y);
|
|
|
|
break;
|
|
|
|
|
|
|
|
case MAV_FRAME_LOCAL_NED:
|
|
|
|
default:
|
|
|
|
// MAV_FRAME_LOCAL_NED is interpreted as an offset from EKF origin
|
|
|
|
target_loc = ekf_origin;
|
|
|
|
target_loc.offset(packet.x, packet.y);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
2016-08-23 03:04:30 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
float target_speed = 0.0f;
|
|
|
|
float target_yaw_cd = 0.0f;
|
2017-12-04 23:12:25 -04:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
// consume velocity and convert to target speed and heading
|
|
|
|
if (!vel_ignore) {
|
|
|
|
const float speed_max = rover.control_mode->get_speed_default();
|
|
|
|
// convert vector length into a speed
|
|
|
|
target_speed = constrain_float(safe_sqrt(sq(packet.vx) + sq(packet.vy)), -speed_max, speed_max);
|
|
|
|
// convert vector direction to target yaw
|
|
|
|
target_yaw_cd = degrees(atan2f(packet.vy, packet.vx)) * 100.0f;
|
2017-08-01 07:09:05 -03:00
|
|
|
|
2021-01-04 05:23:55 -04: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
|
|
|
}
|
2021-01-04 05:23:55 -04:00
|
|
|
}
|
|
|
|
|
|
|
|
// consume yaw heading
|
|
|
|
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);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
// consume yaw rate
|
|
|
|
float target_turn_rate_cds = 0.0f;
|
|
|
|
if (!yaw_rate_ignore) {
|
|
|
|
target_turn_rate_cds = ToDeg(packet.yaw_rate) * 100.0f;
|
|
|
|
}
|
|
|
|
|
|
|
|
// handling case when both velocity and either yaw or yaw-rate are provided
|
|
|
|
// by default, we consider that the rover will drive forward
|
|
|
|
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
|
|
|
|
if (is_negative(packet.vx)) {
|
|
|
|
speed_dir = -1.0f;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// set guided mode targets
|
|
|
|
if (!pos_ignore) {
|
|
|
|
// consume position target
|
|
|
|
if (!rover.mode_guided.set_desired_location(target_loc)) {
|
|
|
|
// GCS will need to monitor desired location to
|
|
|
|
// see if they are having an effect.
|
|
|
|
}
|
|
|
|
} else if (!vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume velocity
|
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
|
|
|
} else if (!vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
|
|
|
// consume velocity and turn rate
|
|
|
|
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, speed_dir * target_speed);
|
|
|
|
} else if (!vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume velocity and heading
|
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
|
|
|
} else if (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 (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);
|
|
|
|
}
|
|
|
|
}
|
2016-08-23 03:04:30 -03:00
|
|
|
|
2021-01-04 00:46:45 -04:00
|
|
|
void GCS_MAVLINK_Rover::handle_set_position_target_global_int(const mavlink_message_t &msg)
|
2021-01-04 05:23:55 -04:00
|
|
|
{
|
|
|
|
// decode packet
|
|
|
|
mavlink_set_position_target_global_int_t packet;
|
|
|
|
mavlink_msg_set_position_target_global_int_decode(&msg, &packet);
|
2017-08-01 07:09:05 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
// exit if vehicle is not in Guided mode
|
|
|
|
if (!rover.control_mode->in_guided_mode()) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
// check for supported coordinate frames
|
|
|
|
if (packet.coordinate_frame != MAV_FRAME_GLOBAL &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_INT &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_RELATIVE_ALT_INT &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT &&
|
|
|
|
packet.coordinate_frame != MAV_FRAME_GLOBAL_TERRAIN_ALT_INT) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
bool pos_ignore = packet.type_mask & MAVLINK_SET_POS_TYPE_MASK_POS_IGNORE;
|
|
|
|
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;
|
|
|
|
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;
|
|
|
|
|
|
|
|
// prepare target position
|
|
|
|
Location target_loc = rover.current_loc;
|
|
|
|
if (!pos_ignore) {
|
|
|
|
// sanity check location
|
|
|
|
if (!check_latlng(packet.lat_int, packet.lon_int)) {
|
|
|
|
// result = MAV_RESULT_FAILED;
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
target_loc.lat = packet.lat_int;
|
|
|
|
target_loc.lng = packet.lon_int;
|
|
|
|
}
|
2016-08-23 03:04:30 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
float target_speed = 0.0f;
|
|
|
|
float target_yaw_cd = 0.0f;
|
2017-12-04 23:12:25 -04:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
// consume velocity and convert to target speed and heading
|
|
|
|
if (!vel_ignore) {
|
|
|
|
const float speed_max = rover.control_mode->get_speed_default();
|
|
|
|
// convert vector length into a speed
|
|
|
|
target_speed = constrain_float(safe_sqrt(sq(packet.vx) + sq(packet.vy)), -speed_max, speed_max);
|
|
|
|
// convert vector direction to target yaw
|
|
|
|
target_yaw_cd = degrees(atan2f(packet.vy, packet.vx)) * 100.0f;
|
|
|
|
}
|
|
|
|
|
|
|
|
// consume yaw heading
|
|
|
|
if (!yaw_ignore) {
|
|
|
|
target_yaw_cd = ToDeg(packet.yaw) * 100.0f;
|
|
|
|
}
|
2021-09-13 04:54:21 -03:00
|
|
|
|
2021-01-04 05:23:55 -04:00
|
|
|
// consume yaw rate
|
|
|
|
float target_turn_rate_cds = 0.0f;
|
|
|
|
if (!yaw_rate_ignore) {
|
|
|
|
target_turn_rate_cds = ToDeg(packet.yaw_rate) * 100.0f;
|
|
|
|
}
|
|
|
|
|
|
|
|
// handling case when both velocity and either yaw or yaw-rate are provided
|
|
|
|
// by default, we consider that the rover will drive forward
|
|
|
|
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
|
|
|
|
if (is_negative(packet.vx)) {
|
|
|
|
speed_dir = -1.0f;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// set guided mode targets
|
|
|
|
if (!pos_ignore) {
|
|
|
|
// consume position target
|
|
|
|
if (!rover.mode_guided.set_desired_location(target_loc)) {
|
|
|
|
// GCS will just need to look at desired location
|
|
|
|
// outputs to see if it having an effect.
|
|
|
|
}
|
|
|
|
} else if (!vel_ignore && acc_ignore && yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume velocity
|
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
|
|
|
} else if (!vel_ignore && acc_ignore && yaw_ignore && !yaw_rate_ignore) {
|
|
|
|
// consume velocity and turn rate
|
|
|
|
rover.mode_guided.set_desired_turn_rate_and_speed(target_turn_rate_cds, speed_dir * target_speed);
|
|
|
|
} else if (!vel_ignore && acc_ignore && !yaw_ignore && yaw_rate_ignore) {
|
|
|
|
// consume velocity
|
|
|
|
rover.mode_guided.set_desired_heading_and_speed(target_yaw_cd, speed_dir * target_speed);
|
|
|
|
} else if (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 (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);
|
|
|
|
}
|
|
|
|
}
|
2016-08-23 03:04:30 -03:00
|
|
|
|
2021-01-04 00:46:45 -04:00
|
|
|
void GCS_MAVLINK_Rover::handle_radio(const mavlink_message_t &msg)
|
2021-01-04 05:23:55 -04:00
|
|
|
{
|
2024-01-10 00:21:43 -04:00
|
|
|
#if HAL_LOGGING_ENABLED
|
2021-01-04 05:23:55 -04:00
|
|
|
handle_radio_status(msg, rover.should_log(MASK_LOG_PM));
|
2024-01-10 00:21:43 -04:00
|
|
|
#else
|
|
|
|
handle_radio_status(msg, false);
|
|
|
|
#endif
|
2021-01-04 05:23:55 -04:00
|
|
|
}
|
2012-05-14 15:33:03 -03:00
|
|
|
|
2022-06-19 02:52:02 -03:00
|
|
|
/*
|
|
|
|
handle a LANDING_TARGET command. The timestamp has been jitter corrected
|
|
|
|
*/
|
|
|
|
void GCS_MAVLINK_Rover::handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms)
|
|
|
|
{
|
2023-03-22 05:45:41 -03:00
|
|
|
#if AC_PRECLAND_ENABLED
|
2022-06-19 02:52:02 -03:00
|
|
|
rover.precland.handle_msg(packet, timestamp_ms);
|
|
|
|
#endif
|
|
|
|
}
|
2012-04-30 04:17:14 -03:00
|
|
|
|
2018-03-28 22:02:36 -03:00
|
|
|
uint64_t GCS_MAVLINK_Rover::capabilities() const
|
|
|
|
{
|
|
|
|
return (MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT |
|
|
|
|
MAV_PROTOCOL_CAPABILITY_MISSION_INT |
|
|
|
|
MAV_PROTOCOL_CAPABILITY_COMMAND_INT |
|
|
|
|
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED |
|
|
|
|
MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT |
|
|
|
|
MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET |
|
|
|
|
GCS_MAVLINK::capabilities());
|
|
|
|
}
|
2021-07-06 07:53:38 -03:00
|
|
|
|
|
|
|
#if HAL_HIGH_LATENCY2_ENABLED
|
|
|
|
uint8_t GCS_MAVLINK_Rover::high_latency_tgt_heading() const
|
|
|
|
{
|
|
|
|
const Mode *control_mode = rover.control_mode;
|
|
|
|
if (rover.control_mode->is_autopilot_mode()) {
|
|
|
|
// need to convert -180->180 to 0->360/2
|
|
|
|
return wrap_360(control_mode->wp_bearing()) / 2;
|
|
|
|
}
|
2022-02-14 08:09:10 -04:00
|
|
|
return 0;
|
2021-07-06 07:53:38 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
uint16_t GCS_MAVLINK_Rover::high_latency_tgt_dist() const
|
|
|
|
{
|
|
|
|
const Mode *control_mode = rover.control_mode;
|
|
|
|
if (rover.control_mode->is_autopilot_mode()) {
|
|
|
|
// return units are dm
|
|
|
|
return MIN((control_mode->get_distance_to_destination()) / 10, UINT16_MAX);
|
|
|
|
}
|
2022-02-14 08:09:10 -04:00
|
|
|
return 0;
|
2021-07-06 07:53:38 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t GCS_MAVLINK_Rover::high_latency_tgt_airspeed() const
|
|
|
|
{
|
|
|
|
const Mode *control_mode = rover.control_mode;
|
|
|
|
if (rover.control_mode->is_autopilot_mode()) {
|
|
|
|
// return units are m/s*5
|
|
|
|
return MIN((vfr_hud_airspeed() - control_mode->speed_error()) * 5, UINT8_MAX);
|
|
|
|
}
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t GCS_MAVLINK_Rover::high_latency_wind_speed() const
|
|
|
|
{
|
|
|
|
if (rover.g2.windvane.enabled()) {
|
|
|
|
// return units are m/s*5
|
|
|
|
return MIN(rover.g2.windvane.get_true_wind_speed() * 5, UINT8_MAX);
|
|
|
|
}
|
2022-02-14 08:09:10 -04:00
|
|
|
return 0;
|
2021-07-06 07:53:38 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
uint8_t GCS_MAVLINK_Rover::high_latency_wind_direction() const
|
|
|
|
{
|
|
|
|
if (rover.g2.windvane.enabled()) {
|
|
|
|
// return units are deg/2
|
|
|
|
return wrap_360(degrees(rover.g2.windvane.get_true_wind_direction_rad())) / 2;
|
|
|
|
}
|
2022-02-14 08:09:10 -04:00
|
|
|
return 0;
|
2021-07-06 07:53:38 -03:00
|
|
|
}
|
2021-08-17 09:09:00 -03:00
|
|
|
#endif // HAL_HIGH_LATENCY2_ENABLED
|