Browse Source

Sub: add airspeed sensors

zr-v5.1
Iampete1 5 years ago committed by Andrew Tridgell
parent
commit
d197ec4072
  1. 1
      ArduSub/ArduSub.cpp
  2. 7
      ArduSub/Parameters.cpp
  3. 3
      ArduSub/Parameters.h
  4. 1
      ArduSub/Sub.h
  5. 8
      ArduSub/sensors.cpp
  6. 2
      ArduSub/system.cpp

1
ArduSub/ArduSub.cpp

@ -78,6 +78,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { @@ -78,6 +78,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
#ifdef USERHOOK_SUPERSLOWLOOP
SCHED_TASK(userhook_SuperSlowLoop, 1, 75),
#endif
SCHED_TASK(read_airspeed, 10, 100),
};
void Sub::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,

7
ArduSub/Parameters.cpp

@ -632,13 +632,18 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { @@ -632,13 +632,18 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(scripting, "SCR_", 18, ParametersG2, AP_Scripting),
#endif
// @Group: ARSPD
// @Path: ../libraries/AP_Airspeed/AP_Airspeed.cpp
AP_SUBGROUPINFO(airspeed, "ARSPD", 19, ParametersG2, AP_Airspeed),
AP_GROUPEND
};
/*
constructor for g2 object
*/
ParametersG2::ParametersG2()
ParametersG2::ParametersG2():
airspeed()
{
AP_Param::setup_object_defaults(this, var_info);
}

3
ArduSub/Parameters.h

@ -335,6 +335,9 @@ public: @@ -335,6 +335,9 @@ public:
AP_Scripting scripting;
#endif // ENABLE_SCRIPTING
// Airspeed
AP_Airspeed airspeed;
};
extern const AP_Param::Info var_info[];

1
ArduSub/Sub.h

@ -610,6 +610,7 @@ private: @@ -610,6 +610,7 @@ private:
void auto_spline_start(const Location& destination, bool stopped_at_start, AC_WPNav::spline_segment_end_type seg_end_type, const Location& next_destination);
void log_init(void);
void accel_cal_update(void);
void read_airspeed();
void failsafe_leak_check();
void failsafe_internal_pressure_check();

8
ArduSub/sensors.cpp

@ -107,3 +107,11 @@ void Sub::accel_cal_update() @@ -107,3 +107,11 @@ void Sub::accel_cal_update()
ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0));
}
}
/*
ask airspeed sensor for a new value, duplicated from plane
*/
void Sub::read_airspeed()
{
g2.airspeed.update(should_log(MASK_LOG_IMU));
}

2
ArduSub/system.cpp

@ -165,6 +165,8 @@ void Sub::init_ardupilot() @@ -165,6 +165,8 @@ void Sub::init_ardupilot()
g2.scripting.init();
#endif // ENABLE_SCRIPTING
g2.airspeed.init();
// we don't want writes to the serial port to cause us to pause
// mid-flight, so set the serial ports non-blocking once we are
// ready to fly

Loading…
Cancel
Save