mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: split DISTANCE_SENSOR onto its own ap_message id
This commit is contained in:
parent
77be393ad4
commit
f8f5faa6b9
@ -145,15 +145,15 @@ int16_t GCS_MAVLINK_Rover::vfr_hud_throttle() const
|
|||||||
return rover.g2.motors.get_throttle();
|
return rover.g2.motors.get_throttle();
|
||||||
}
|
}
|
||||||
|
|
||||||
void Rover::send_rangefinder(mavlink_channel_t chan)
|
void GCS_MAVLINK_Rover::send_rangefinder() const
|
||||||
{
|
{
|
||||||
float distance_cm;
|
float distance_cm;
|
||||||
float voltage;
|
float voltage;
|
||||||
bool got_one = false;
|
bool got_one = false;
|
||||||
|
|
||||||
// report smaller distance of all rangefinders
|
// report smaller distance of all rangefinders
|
||||||
for (uint8_t i=0; i<rangefinder.num_sensors(); i++) {
|
for (uint8_t i=0; i<rover.rangefinder.num_sensors(); i++) {
|
||||||
AP_RangeFinder_Backend *s = rangefinder.get_backend(i);
|
AP_RangeFinder_Backend *s = rover.rangefinder.get_backend(i);
|
||||||
if (s == nullptr) {
|
if (s == nullptr) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
@ -340,13 +340,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
|||||||
rover.send_servo_out(chan);
|
rover.send_servo_out(chan);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_RANGEFINDER:
|
|
||||||
CHECK_PAYLOAD_SIZE(RANGEFINDER);
|
|
||||||
rover.send_rangefinder(chan);
|
|
||||||
send_distance_sensor();
|
|
||||||
send_proximity();
|
|
||||||
break;
|
|
||||||
|
|
||||||
case MSG_RPM:
|
case MSG_RPM:
|
||||||
CHECK_PAYLOAD_SIZE(RPM);
|
CHECK_PAYLOAD_SIZE(RPM);
|
||||||
rover.send_wheel_encoder(chan);
|
rover.send_wheel_encoder(chan);
|
||||||
@ -512,6 +505,7 @@ static const ap_message STREAM_EXTRA3_msgs[] = {
|
|||||||
MSG_HWSTATUS,
|
MSG_HWSTATUS,
|
||||||
MSG_WIND,
|
MSG_WIND,
|
||||||
MSG_RANGEFINDER,
|
MSG_RANGEFINDER,
|
||||||
|
MSG_DISTANCE_SENSOR,
|
||||||
MSG_SYSTEM_TIME,
|
MSG_SYSTEM_TIME,
|
||||||
MSG_BATTERY2,
|
MSG_BATTERY2,
|
||||||
MSG_BATTERY_STATUS,
|
MSG_BATTERY_STATUS,
|
||||||
|
@ -48,4 +48,6 @@ private:
|
|||||||
|
|
||||||
int16_t vfr_hud_throttle() const override;
|
int16_t vfr_hud_throttle() const override;
|
||||||
|
|
||||||
|
void send_rangefinder() const override;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
@ -434,7 +434,6 @@ private:
|
|||||||
void send_sys_status(mavlink_channel_t chan);
|
void send_sys_status(mavlink_channel_t chan);
|
||||||
void send_nav_controller_output(mavlink_channel_t chan);
|
void send_nav_controller_output(mavlink_channel_t chan);
|
||||||
void send_servo_out(mavlink_channel_t chan);
|
void send_servo_out(mavlink_channel_t chan);
|
||||||
void send_rangefinder(mavlink_channel_t chan);
|
|
||||||
void send_pid_tuning(mavlink_channel_t chan);
|
void send_pid_tuning(mavlink_channel_t chan);
|
||||||
void send_wheel_encoder(mavlink_channel_t chan);
|
void send_wheel_encoder(mavlink_channel_t chan);
|
||||||
void send_fence_status(mavlink_channel_t chan);
|
void send_fence_status(mavlink_channel_t chan);
|
||||||
|
Loading…
Reference in New Issue
Block a user