|
|
|
@ -155,19 +155,6 @@ void GCS_MAVLINK_Rover::send_rangefinder() const
@@ -155,19 +155,6 @@ void GCS_MAVLINK_Rover::send_rangefinder() const
|
|
|
|
|
voltage); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
send RPM packet |
|
|
|
|
*/ |
|
|
|
|
void Rover::send_rpm(mavlink_channel_t chan) |
|
|
|
|
{ |
|
|
|
|
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) { |
|
|
|
|
mavlink_msg_rpm_send( |
|
|
|
|
chan, |
|
|
|
|
rpm_sensor.get_rpm(0), |
|
|
|
|
rpm_sensor.get_rpm(1)); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
send PID tuning message |
|
|
|
|
*/ |
|
|
|
@ -323,11 +310,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
@@ -323,11 +310,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
|
|
|
|
rover.send_servo_out(chan); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MSG_RPM: |
|
|
|
|
CHECK_PAYLOAD_SIZE(RPM); |
|
|
|
|
rover.send_rpm(chan); |
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MSG_WHEEL_DISTANCE: |
|
|
|
|
CHECK_PAYLOAD_SIZE(WHEEL_DISTANCE); |
|
|
|
|
rover.send_wheel_encoder_distance(chan); |
|
|
|
|