mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: adding AP_RPM
This commit is contained in:
parent
c422a21f55
commit
692281b273
@ -66,6 +66,7 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
|
||||
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_aux_all, 10, 200),
|
||||
SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300),
|
||||
SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200),
|
||||
SCHED_TASK(rpm_update, 10, 100),
|
||||
#if MOUNT == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200),
|
||||
#endif
|
||||
|
@ -160,6 +160,19 @@ 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
|
||||
*/
|
||||
@ -325,7 +338,7 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
|
||||
|
||||
case MSG_RPM:
|
||||
CHECK_PAYLOAD_SIZE(RPM);
|
||||
rover.send_wheel_encoder(chan);
|
||||
rover.send_rpm(chan);
|
||||
break;
|
||||
|
||||
case MSG_WHEEL_DISTANCE:
|
||||
|
@ -409,6 +409,10 @@ const AP_Param::Info Rover::var_info[] = {
|
||||
GOBJECTN(EKF3, NavEKF3, "EK3_", NavEKF3),
|
||||
#endif
|
||||
|
||||
// @Group: RPM
|
||||
// @Path: ../libraries/AP_RPM/AP_RPM.cpp
|
||||
GOBJECT(rpm_sensor, "RPM", AP_RPM),
|
||||
|
||||
// @Group: MIS_
|
||||
// @Path: ../libraries/AP_Mission/AP_Mission.cpp
|
||||
GOBJECTN(mode_auto.mission, mission, "MIS_", AP_Mission),
|
||||
|
@ -58,7 +58,8 @@ public:
|
||||
|
||||
// 97: RSSI
|
||||
k_param_rssi = 97,
|
||||
|
||||
k_param_rpm_sensor, // rpm sensor 98
|
||||
|
||||
// 100: Arming parameters
|
||||
k_param_arming = 100,
|
||||
|
||||
|
@ -54,6 +54,7 @@
|
||||
#include <AP_RangeFinder/AP_RangeFinder.h> // Range finder library
|
||||
#include <AP_RCMapper/AP_RCMapper.h> // RC input mapping library
|
||||
#include <AP_Relay/AP_Relay.h> // APM relay
|
||||
#include <AP_RPM/AP_RPM.h>
|
||||
#include <AP_RSSI/AP_RSSI.h> // RSSI Library
|
||||
#include <AP_Scheduler/AP_Scheduler.h> // main loop scheduler
|
||||
#include <AP_SerialManager/AP_SerialManager.h> // Serial manager library
|
||||
@ -177,6 +178,9 @@ private:
|
||||
AP_Int8 *modes;
|
||||
const uint8_t num_modes = 6;
|
||||
|
||||
// AP_RPM Module
|
||||
AP_RPM rpm_sensor;
|
||||
|
||||
// Inertial Navigation EKF
|
||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||
NavEKF2 EKF2{&ahrs, rangefinder};
|
||||
@ -441,6 +445,7 @@ private:
|
||||
void send_nav_controller_output(mavlink_channel_t chan);
|
||||
void send_servo_out(mavlink_channel_t chan);
|
||||
void send_pid_tuning(mavlink_channel_t chan);
|
||||
void send_rpm(mavlink_channel_t chan);
|
||||
void send_wheel_encoder(mavlink_channel_t chan);
|
||||
void send_wheel_encoder_distance(mavlink_channel_t chan);
|
||||
|
||||
@ -509,6 +514,7 @@ private:
|
||||
void set_servos(void);
|
||||
|
||||
// system.cpp
|
||||
void rpm_update(void);
|
||||
void init_ardupilot();
|
||||
void startup_ground(void);
|
||||
void update_ahrs_flyforward();
|
||||
|
@ -252,6 +252,18 @@ void Rover::read_airspeed(void)
|
||||
g2.airspeed.update(should_log(MASK_LOG_IMU));
|
||||
}
|
||||
|
||||
/*
|
||||
update RPM sensors
|
||||
*/
|
||||
void Rover::rpm_update(void)
|
||||
{
|
||||
rpm_sensor.update();
|
||||
if (rpm_sensor.enabled(0) || rpm_sensor.enabled(1)) {
|
||||
if (should_log(MASK_LOG_RC)) {
|
||||
logger.Write_RPM(rpm_sensor);
|
||||
}
|
||||
}
|
||||
}
|
||||
// update error mask of sensors and subsystems. The mask
|
||||
// uses the MAV_SYS_STATUS_* values from mavlink. If a bit is set
|
||||
// then it indicates that the sensor or subsystem is present but
|
||||
|
@ -62,6 +62,9 @@ void Rover::init_ardupilot()
|
||||
|
||||
battery.init();
|
||||
|
||||
// Initialise RPM sensor
|
||||
rpm_sensor.init();
|
||||
|
||||
rssi.init();
|
||||
|
||||
g2.airspeed.init();
|
||||
|
Loading…
Reference in New Issue
Block a user