2015-05-13 00:16:45 -03:00
# include "Rover.h"
2017-08-08 02:58:52 -03:00
# include <AP_RangeFinder/RangeFinder_Backend.h>
2019-02-13 21:59:27 -04:00
# include <AP_VisualOdom/AP_VisualOdom.h>
2017-08-08 02:58:52 -03:00
2019-03-15 22:10:33 -03:00
// check for new compass data - 10Hz
void Rover : : update_compass ( void )
{
2019-03-24 00:25:27 -03:00
if ( AP : : compass ( ) . enabled ( ) & & compass . read ( ) ) {
2019-03-15 22:10:33 -03:00
ahrs . set_compass ( & compass ) ;
}
}
// Save compass offsets
void Rover : : compass_save ( ) {
2019-03-24 00:25:27 -03:00
if ( AP : : compass ( ) . enabled ( ) & &
2019-03-15 22:10:33 -03:00
compass . get_learn_type ( ) > = Compass : : LEARN_INTERNAL & &
! arming . is_armed ( ) ) {
compass . save_offsets ( ) ;
}
}
2017-04-03 17:46:12 -03:00
// 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
2019-10-17 08:03:18 -03:00
// save cumulative distances at current time (in meters) for reporting to GCS
for ( uint8_t i = 0 ; i < g2 . wheel_encoder . num_sensors ( ) ; i + + ) {
wheel_encoder_last_distance_m [ i ] = g2 . wheel_encoder . get_distance ( i ) ;
}
// send wheel encoder delta angle and delta time to EKF
// this should not be done at more than 50hz
2017-07-20 03:12:09 -03:00
// initialise on first iteration
2019-10-17 08:03:18 -03:00
if ( ! wheel_encoder_initialised ) {
wheel_encoder_initialised = true ;
2017-08-03 06:53:22 -03:00
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 ) ;
2019-10-17 08:03:18 -03:00
wheel_encoder_last_reading_ms [ i ] = g2 . wheel_encoder . get_last_reading_ms ( i ) ;
2017-07-20 03:12:09 -03:00
}
return ;
}
2019-10-17 08:03:18 -03:00
// on each iteration send data from alternative wheel encoders
wheel_encoder_last_index_sent + + ;
if ( wheel_encoder_last_index_sent > = g2 . wheel_encoder . num_sensors ( ) ) {
wheel_encoder_last_index_sent = 0 ;
}
2019-01-25 22:14:00 -04:00
2019-10-17 08:03:18 -03:00
// get current time, total delta angle (since startup) and update time from sensor
const float curr_angle_rad = g2 . wheel_encoder . get_delta_angle ( wheel_encoder_last_index_sent ) ;
const uint32_t sensor_reading_ms = g2 . wheel_encoder . get_last_reading_ms ( wheel_encoder_last_index_sent ) ;
const uint32_t now_ms = AP_HAL : : millis ( ) ;
2017-07-20 03:12:09 -03:00
2019-10-17 08:03:18 -03:00
// calculate angular change (in radians)
const float delta_angle = curr_angle_rad - wheel_encoder_last_angle_rad [ wheel_encoder_last_index_sent ] ;
wheel_encoder_last_angle_rad [ wheel_encoder_last_index_sent ] = curr_angle_rad ;
2017-07-20 03:12:09 -03:00
2019-10-17 08:03:18 -03:00
// calculate delta time using time between sensor readings or time since last send to ekf (whichever is shorter)
uint32_t sensor_diff_ms = sensor_reading_ms - wheel_encoder_last_reading_ms [ wheel_encoder_last_index_sent ] ;
if ( sensor_diff_ms = = 0 | | sensor_diff_ms > 100 ) {
// if no sensor update or time difference between sensor readings is too long use time since last send to ekf
sensor_diff_ms = now_ms - wheel_encoder_last_reading_ms [ wheel_encoder_last_index_sent ] ;
wheel_encoder_last_reading_ms [ wheel_encoder_last_index_sent ] = now_ms ;
} else {
wheel_encoder_last_reading_ms [ wheel_encoder_last_index_sent ] = sensor_reading_ms ;
2017-07-20 03:12:09 -03:00
}
2019-10-17 08:03:18 -03:00
const float delta_time = sensor_diff_ms * 0.001f ;
2017-07-20 03:12:09 -03:00
2019-10-17 08:03:18 -03:00
/* 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_reading_ms [ wheel_encoder_last_index_sent ] ,
g2 . wheel_encoder . get_pos_offset ( wheel_encoder_last_index_sent ) ,
g2 . wheel_encoder . get_wheel_radius ( wheel_encoder_last_index_sent ) ) ;
2017-07-11 23:02:51 -03:00
}
2015-10-21 18:22:45 -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;
2016-12-20 09:33:45 -04:00
float trim_roll , trim_pitch ;
if ( ins . get_new_trim ( trim_roll , trim_pitch ) ) {
2015-10-21 18:22:45 -03:00
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 ( ) ;
}
2018-09-14 04:09:07 -03:00
/*
ask airspeed sensor for a new value , duplicated from plane
*/
void Rover : : read_airspeed ( void )
{
2018-11-16 12:15:37 -04:00
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 ) ;
}
}
}