ardupilot/APMrover2/sensors.cpp

147 lines
4.6 KiB
C++
Raw Normal View History

2015-05-13 00:16:45 -03:00
#include "Rover.h"
#include <AP_RangeFinder/RangeFinder_Backend.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
// check for new compass data - 10Hz
void Rover::update_compass(void)
{
if (AP::compass().enabled() && compass.read()) {
ahrs.set_compass(&compass);
}
}
// Save compass offsets
void Rover::compass_save() {
if (AP::compass().enabled() &&
compass.get_learn_type() >= Compass::LEARN_INTERNAL &&
!arming.is_armed()) {
compass.save_offsets();
}
}
// init beacons used for non-gps position estimates
void Rover::init_beacon()
{
g2.beacon.init();
}
2017-06-01 04:39:49 -03:00
// init visual odometry sensor
void Rover::init_visual_odom()
{
g2.visual_odom.init();
}
2017-07-11 23:02:51 -03:00
// update wheel encoders
void Rover::update_wheel_encoder()
{
2017-07-20 03:12:09 -03:00
// exit immediately if not enabled
if (g2.wheel_encoder.num_sensors() == 0) {
return;
}
// update encoders
2017-07-11 23:02:51 -03:00
g2.wheel_encoder.update();
2017-07-20 03:12:09 -03:00
// initialise on first iteration
const uint32_t now = AP_HAL::millis();
2017-07-20 03:12:09 -03:00
if (wheel_encoder_last_ekf_update_ms == 0) {
wheel_encoder_last_ekf_update_ms = now;
for (uint8_t i = 0; i < g2.wheel_encoder.num_sensors(); i++) {
2017-07-20 03:12:09 -03:00
wheel_encoder_last_angle_rad[i] = g2.wheel_encoder.get_delta_angle(i);
wheel_encoder_last_update_ms[i] = g2.wheel_encoder.get_last_reading_ms(i);
}
return;
}
// calculate delta angle and delta time and send to EKF
// use time of last ping from wheel encoder
// send delta time (time between this wheel encoder time and previous wheel encoder time)
// in case where wheel hasn't moved, count = 0 (cap the delta time at 50ms - or system time)
// use system clock of last update instead of time of last ping
const float system_dt = (now - wheel_encoder_last_ekf_update_ms) / 1000.0f;
for (uint8_t i = 0; i < g2.wheel_encoder.num_sensors(); i++) {
2017-07-20 03:12:09 -03:00
// calculate angular change (in radians)
const float curr_angle_rad = g2.wheel_encoder.get_delta_angle(i);
const float delta_angle = curr_angle_rad - wheel_encoder_last_angle_rad[i];
2017-07-20 03:12:09 -03:00
wheel_encoder_last_angle_rad[i] = curr_angle_rad;
// save cumulative distances at current time (in meters)
wheel_encoder_last_distance_m[i] = g2.wheel_encoder.get_distance(i);
2017-07-20 03:12:09 -03:00
// calculate delta time
float delta_time;
const uint32_t latest_sensor_update_ms = g2.wheel_encoder.get_last_reading_ms(i);
const uint32_t sensor_diff_ms = latest_sensor_update_ms - wheel_encoder_last_update_ms[i];
2017-07-20 03:12:09 -03:00
// if we have not received any sensor updates, or time difference is too high then use time since last update to the ekf
// check for old or insane sensor update times
if (sensor_diff_ms == 0 || sensor_diff_ms > 100) {
delta_time = system_dt;
wheel_encoder_last_update_ms[i] = wheel_encoder_last_ekf_update_ms;
} else {
delta_time = sensor_diff_ms / 1000.0f;
wheel_encoder_last_update_ms[i] = latest_sensor_update_ms;
}
/* delAng is the measured change in angular position from the previous measurement where a positive rotation is produced by forward motion of the vehicle (rad)
* delTime is the time interval for the measurement of delAng (sec)
* timeStamp_ms is the time when the rotation was last measured (msec)
* posOffset is the XYZ body frame position of the wheel hub (m)
*/
EKF3.writeWheelOdom(delta_angle, delta_time, wheel_encoder_last_update_ms[i], g2.wheel_encoder.get_pos_offset(i), g2.wheel_encoder.get_wheel_radius(i));
2017-07-20 03:12:09 -03:00
}
// record system time update for next iteration
wheel_encoder_last_ekf_update_ms = now;
2017-07-11 23:02:51 -03:00
}
// Accel calibration
void Rover::accel_cal_update() {
if (hal.util->get_soft_armed()) {
return;
}
ins.acal_update();
// check if new trim values, and set them float trim_roll, trim_pitch;
float trim_roll, trim_pitch;
if (ins.get_new_trim(trim_roll, trim_pitch)) {
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
}
}
2017-07-13 08:36:44 -03:00
// read the rangefinders
void Rover::read_rangefinders(void)
2013-03-21 18:49:51 -03:00
{
2017-07-13 08:36:44 -03:00
rangefinder.update();
2018-06-11 08:10:53 -03:00
Log_Write_Depth();
2013-03-21 18:49:51 -03:00
}
2016-07-21 22:24:35 -03:00
2017-08-16 07:57:42 -03:00
// initialise proximity sensor
void Rover::init_proximity(void)
{
g2.proximity.init();
g2.proximity.set_rangefinder(&rangefinder);
}
2018-09-14 04:09:07 -03:00
/*
ask airspeed sensor for a new value, duplicated from plane
*/
void Rover::read_airspeed(void)
{
g2.airspeed.update(should_log(MASK_LOG_IMU));
2018-09-14 04:09:07 -03:00
}
2018-12-30 16:43:39 -04:00
/*
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);
}
}
}