Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Rover/Rover.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/*16This is the ArduRover firmware. It was originally derived from17ArduPlane by Jean-Louis Naudin (JLN), and then rewritten after the18AP_HAL merge by Andrew Tridgell1920Maintainer: Randy Mackay, Grant Morphett2122Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Andrew Tridgell, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler, Jean-Louis Naudin, Grant Morphett2324Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier2526APMrover alpha version tester: Franco Borasio, Daniel Chapelat...2728Please contribute your ideas! See https://ardupilot.org/dev for details29*/3031#include "Rover.h"3233#define FORCE_VERSION_H_INCLUDE34#include "version.h"35#undef FORCE_VERSION_H_INCLUDE3637const AP_HAL::HAL& hal = AP_HAL::get_HAL();3839#define SCHED_TASK(func, _interval_ticks, _max_time_micros, _priority) SCHED_TASK_CLASS(Rover, &rover, func, _interval_ticks, _max_time_micros, _priority)4041/*42scheduler table - all regular tasks should be listed here.4344All entries in this table must be ordered by priority.4546This table is interleaved with the table in AP_Vehicle to determine47the order in which tasks are run. Convenience methods SCHED_TASK48and SCHED_TASK_CLASS are provided to build entries in this structure:4950SCHED_TASK arguments:51- name of static function to call52- rate (in Hertz) at which the function should be called53- expected time (in MicroSeconds) that the function should take to run54- priority (0 through 255, lower number meaning higher priority)5556SCHED_TASK_CLASS arguments:57- class name of method to be called58- instance on which to call the method59- method to call on that instance60- rate (in Hertz) at which the method should be called61- expected time (in MicroSeconds) that the method should take to run62- priority (0 through 255, lower number meaning higher priority)6364scheduler table - all regular tasks are listed here, along with how65often they should be called (in Hz) and the maximum time66they are expected to take (in microseconds)67*/68const AP_Scheduler::Task Rover::scheduler_tasks[] = {69// Function name, Hz, us,70SCHED_TASK(read_radio, 50, 200, 3),71SCHED_TASK(ahrs_update, 400, 400, 6),72#if AP_RANGEFINDER_ENABLED73SCHED_TASK(read_rangefinders, 50, 200, 9),74#endif75#if AP_OPTICALFLOW_ENABLED76SCHED_TASK_CLASS(AP_OpticalFlow, &rover.optflow, update, 200, 160, 11),77#endif78SCHED_TASK(update_current_mode, 400, 200, 12),79SCHED_TASK(set_servos, 400, 200, 15),80SCHED_TASK_CLASS(AP_GPS, &rover.gps, update, 50, 300, 18),81SCHED_TASK_CLASS(AP_Baro, &rover.barometer, update, 10, 200, 21),82#if AP_BEACON_ENABLED83SCHED_TASK_CLASS(AP_Beacon, &rover.g2.beacon, update, 50, 200, 24),84#endif85#if HAL_PROXIMITY_ENABLED86SCHED_TASK_CLASS(AP_Proximity, &rover.g2.proximity, update, 50, 200, 27),87#endif88SCHED_TASK_CLASS(AP_WindVane, &rover.g2.windvane, update, 20, 100, 30),89SCHED_TASK(update_wheel_encoder, 50, 200, 36),90SCHED_TASK(update_compass, 10, 200, 39),91#if HAL_LOGGING_ENABLED92SCHED_TASK(update_logging1, 10, 200, 45),93SCHED_TASK(update_logging2, 10, 200, 48),94#endif95SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_receive, 400, 500, 51),96SCHED_TASK_CLASS(GCS, (GCS*)&rover._gcs, update_send, 400, 1000, 54),97SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_mode_switch, 7, 200, 57),98SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&rover.g2.rc_channels, read_aux_all, 10, 200, 60),99SCHED_TASK_CLASS(AP_BattMonitor, &rover.battery, read, 10, 300, 63),100#if AP_SERVORELAYEVENTS_ENABLED101SCHED_TASK_CLASS(AP_ServoRelayEvents, &rover.ServoRelayEvents, update_events, 50, 200, 66),102#endif103#if AC_PRECLAND_ENABLED104SCHED_TASK(update_precland, 400, 50, 70),105#endif106#if AP_RPM_ENABLED107SCHED_TASK_CLASS(AP_RPM, &rover.rpm_sensor, update, 10, 100, 72),108#endif109#if HAL_MOUNT_ENABLED110SCHED_TASK_CLASS(AP_Mount, &rover.camera_mount, update, 50, 200, 75),111#endif112#if AP_CAMERA_ENABLED113SCHED_TASK_CLASS(AP_Camera, &rover.camera, update, 50, 200, 78),114#endif115SCHED_TASK(gcs_failsafe_check, 10, 200, 81),116SCHED_TASK(fence_check, 10, 200, 84),117SCHED_TASK(ekf_check, 10, 100, 87),118SCHED_TASK_CLASS(ModeSmartRTL, &rover.mode_smartrtl, save_position, 3, 200, 90),119SCHED_TASK(one_second_loop, 1, 1500, 96),120#if HAL_SPRAYER_ENABLED121SCHED_TASK_CLASS(AC_Sprayer, &rover.g2.sprayer, update, 3, 90, 99),122#endif123SCHED_TASK(compass_save, 0.1, 200, 105),124#if HAL_LOGGING_ENABLED125SCHED_TASK_CLASS(AP_Logger, &rover.logger, periodic_tasks, 50, 300, 108),126#endif127SCHED_TASK_CLASS(AP_InertialSensor, &rover.ins, periodic, 400, 200, 111),128#if HAL_LOGGING_ENABLED129SCHED_TASK_CLASS(AP_Scheduler, &rover.scheduler, update_logging, 0.1, 200, 114),130#endif131#if HAL_BUTTON_ENABLED132SCHED_TASK_CLASS(AP_Button, &rover.button, update, 5, 200, 117),133#endif134SCHED_TASK(crash_check, 10, 200, 123),135SCHED_TASK(cruise_learn_update, 50, 200, 126),136#if AP_ROVER_ADVANCED_FAILSAFE_ENABLED137SCHED_TASK(afs_fs_check, 10, 200, 129),138#endif139};140141142void Rover::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,143uint8_t &task_count,144uint32_t &log_bit)145{146tasks = &scheduler_tasks[0];147task_count = ARRAY_SIZE(scheduler_tasks);148log_bit = MASK_LOG_PM;149}150151constexpr int8_t Rover::_failsafe_priorities[7];152153Rover::Rover(void) :154AP_Vehicle(),155param_loader(var_info),156modes(&g.mode1),157control_mode(&mode_initializing)158{159}160161#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED162// set target location (for use by external control and scripting)163bool Rover::set_target_location(const Location& target_loc)164{165// exit if vehicle is not in Guided mode or Auto-Guided mode166if (!control_mode->in_guided_mode()) {167return false;168}169170return mode_guided.set_desired_location(target_loc);171}172#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED173174#if AP_SCRIPTING_ENABLED175// set target velocity (for use by scripting)176bool Rover::set_target_velocity_NED(const Vector3f& vel_ned)177{178// exit if vehicle is not in Guided mode or Auto-Guided mode179if (!control_mode->in_guided_mode()) {180return false;181}182183// convert vector length into speed184const float target_speed_m = safe_sqrt(sq(vel_ned.x) + sq(vel_ned.y));185186// convert vector direction to target yaw187const float target_yaw_cd = degrees(atan2f(vel_ned.y, vel_ned.x)) * 100.0f;188189// send target heading and speed190mode_guided.set_desired_heading_and_speed(target_yaw_cd, target_speed_m);191192return true;193}194195// set steering and throttle (-1 to +1) (for use by scripting)196bool Rover::set_steering_and_throttle(float steering, float throttle)197{198// exit if vehicle is not in Guided mode or Auto-Guided mode199if (!control_mode->in_guided_mode()) {200return false;201}202203// set steering and throttle204mode_guided.set_steering_and_throttle(steering, throttle);205return true;206}207208// get steering and throttle (-1 to +1) (for use by scripting)209bool Rover::get_steering_and_throttle(float& steering, float& throttle)210{211steering = g2.motors.get_steering() / 4500.0;212throttle = g2.motors.get_throttle() * 0.01;213return true;214}215216// set desired turn rate (degrees/sec) and speed (m/s). Used for scripting217bool Rover::set_desired_turn_rate_and_speed(float turn_rate, float speed)218{219// exit if vehicle is not in Guided mode or Auto-Guided mode220if (!control_mode->in_guided_mode()) {221return false;222}223224// set turn rate and speed. Turn rate is expected in centidegrees/s and speed in meters/s225mode_guided.set_desired_turn_rate_and_speed(turn_rate * 100.0f, speed);226return true;227}228229// set desired nav speed (m/s). Used for scripting.230bool Rover::set_desired_speed(float speed)231{232return control_mode->set_desired_speed(speed);233}234235// get control output (for use in scripting)236// returns true on success and control_value is set to a value in the range -1 to +1237bool Rover::get_control_output(AP_Vehicle::ControlOutput control_output, float &control_value)238{239switch (control_output) {240case AP_Vehicle::ControlOutput::Roll:241control_value = constrain_float(g2.motors.get_roll(), -1.0f, 1.0f);242return true;243case AP_Vehicle::ControlOutput::Pitch:244control_value = constrain_float(g2.motors.get_pitch(), -1.0f, 1.0f);245return true;246case AP_Vehicle::ControlOutput::Walking_Height:247control_value = constrain_float(g2.motors.get_walking_height(), -1.0f, 1.0f);248return true;249case AP_Vehicle::ControlOutput::Throttle:250control_value = constrain_float(g2.motors.get_throttle() * 0.01f, -1.0f, 1.0f);251return true;252case AP_Vehicle::ControlOutput::Yaw:253control_value = constrain_float(g2.motors.get_steering() / 4500.0f, -1.0f, 1.0f);254return true;255case AP_Vehicle::ControlOutput::Lateral:256control_value = constrain_float(g2.motors.get_lateral() * 0.01f, -1.0f, 1.0f);257return true;258case AP_Vehicle::ControlOutput::MainSail:259control_value = constrain_float(g2.motors.get_mainsail() * 0.01f, -1.0f, 1.0f);260return true;261case AP_Vehicle::ControlOutput::WingSail:262control_value = constrain_float(g2.motors.get_wingsail() * 0.01f, -1.0f, 1.0f);263return true;264default:265return false;266}267return false;268}269270// returns true if mode supports NAV_SCRIPT_TIME mission commands271bool Rover::nav_scripting_enable(uint8_t mode)272{273return mode == (uint8_t)mode_auto.mode_number();274}275276// lua scripts use this to retrieve the contents of the active command277bool Rover::nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2, int16_t &arg3, int16_t &arg4)278{279if (control_mode != &mode_auto) {280return false;281}282283return mode_auto.nav_script_time(id, cmd, arg1, arg2, arg3, arg4);284}285286// lua scripts use this to indicate when they have complete the command287void Rover::nav_script_time_done(uint16_t id)288{289if (control_mode != &mode_auto) {290return;291}292293return mode_auto.nav_script_time_done(id);294}295#endif // AP_SCRIPTING_ENABLED296297// update AHRS system298void Rover::ahrs_update()299{300arming.update_soft_armed();301302// AHRS may use movement to calculate heading303update_ahrs_flyforward();304305ahrs.update();306307// update position308have_position = ahrs.get_location(current_loc);309310// set home from EKF if necessary and possible311if (!ahrs.home_is_set()) {312if (!set_home_to_current_location(false)) {313// ignore this failure314}315}316317// if using the EKF get a speed update now (from accelerometers)318Vector3f velocity;319if (ahrs.get_velocity_NED(velocity)) {320ground_speed = velocity.xy().length();321} else if (gps.status() >= AP_GPS::GPS_OK_FIX_3D) {322ground_speed = ahrs.groundspeed();323}324325#if HAL_LOGGING_ENABLED326if (should_log(MASK_LOG_ATTITUDE_FAST)) {327Log_Write_Attitude();328Log_Write_Sail();329}330331if (should_log(MASK_LOG_IMU)) {332AP::ins().Write_IMU();333}334335if (should_log(MASK_LOG_VIDEO_STABILISATION)) {336ahrs.write_video_stabilisation();337}338#endif339}340341/*342check for GCS failsafe - 10Hz343*/344void Rover::gcs_failsafe_check(void)345{346if (g.fs_gcs_enabled == FS_GCS_DISABLED) {347// gcs failsafe disabled348return;349}350351const uint32_t gcs_last_seen_ms = gcs().sysid_myggcs_last_seen_time_ms();352if (gcs_last_seen_ms == 0) {353// we've never seen the GCS, so we never failsafe for not seeing it354return;355}356357// calc time since last gcs update358// note: this only looks at the heartbeat from the device id set by g.sysid_my_gcs359const uint32_t last_gcs_update_ms = millis() - gcs_last_seen_ms;360const uint32_t gcs_timeout_ms = uint32_t(constrain_float(g2.fs_gcs_timeout * 1000.0f, 0.0f, UINT32_MAX));361362const bool do_failsafe = last_gcs_update_ms >= gcs_timeout_ms ? true : false;363364failsafe_trigger(FAILSAFE_EVENT_GCS, "GCS", do_failsafe);365}366367#if HAL_LOGGING_ENABLED368/*369log some key data - 10Hz370*/371void Rover::update_logging1(void)372{373if (should_log(MASK_LOG_ATTITUDE_MED) && !should_log(MASK_LOG_ATTITUDE_FAST)) {374Log_Write_Attitude();375Log_Write_Sail();376}377378if (should_log(MASK_LOG_THR)) {379Log_Write_Throttle();380#if AP_BEACON_ENABLED381g2.beacon.log();382#endif383}384385if (should_log(MASK_LOG_NTUN)) {386Log_Write_Nav_Tuning();387if (g2.pos_control.is_active()) {388g2.pos_control.write_log();389logger.Write_PID(LOG_PIDN_MSG, g2.pos_control.get_vel_pid().get_pid_info_x());390logger.Write_PID(LOG_PIDE_MSG, g2.pos_control.get_vel_pid().get_pid_info_y());391}392}393394#if HAL_PROXIMITY_ENABLED395if (should_log(MASK_LOG_RANGEFINDER)) {396g2.proximity.log();397}398#endif399}400401/*402log some key data - 10Hz403*/404void Rover::update_logging2(void)405{406if (should_log(MASK_LOG_STEERING)) {407Log_Write_Steering();408}409410if (should_log(MASK_LOG_RC)) {411Log_Write_RC();412g2.wheel_encoder.Log_Write();413}414415if (should_log(MASK_LOG_IMU)) {416AP::ins().Write_Vibration();417#if HAL_GYROFFT_ENABLED418gyro_fft.write_log_messages();419#endif420}421#if HAL_MOUNT_ENABLED422if (should_log(MASK_LOG_CAMERA)) {423camera_mount.write_log();424}425#endif426}427#endif // HAL_LOGGING_ENABLED428429/*430once a second events431*/432void Rover::one_second_loop(void)433{434set_control_channels();435436// cope with changes to aux functions437AP::srv().enable_aux_servos();438439// update notify flags440AP_Notify::flags.pre_arm_check = arming.pre_arm_checks(false);441AP_Notify::flags.pre_arm_gps_check = true;442AP_Notify::flags.armed = arming.is_armed();443AP_Notify::flags.flying = hal.util->get_soft_armed();444445// cope with changes to mavlink system ID446mavlink_system.sysid = g.sysid_this_mav;447448// attempt to update home position and baro calibration if not armed:449if (!hal.util->get_soft_armed()) {450update_home();451}452453// need to set "likely flying" when armed to allow for compass454// learning to run455set_likely_flying(hal.util->get_soft_armed());456457// send latest param values to wp_nav458g2.wp_nav.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering());459g2.pos_control.set_turn_params(g2.turn_radius, g2.motors.have_skid_steering());460g2.wheel_rate_control.set_notch_sample_rate(AP::scheduler().get_filtered_loop_rate_hz());461462#if AP_STATS_ENABLED463// Update stats "flying" time464AP::stats()->set_flying(g2.motors.active());465#endif466}467468void Rover::update_current_mode(void)469{470// check for emergency stop471if (SRV_Channels::get_emergency_stop()) {472// relax controllers, motor stopping done at output level473g2.attitude_control.relax_I();474}475476control_mode->update();477}478479// vehicle specific waypoint info helpers480bool Rover::get_wp_distance_m(float &distance) const481{482// see GCS_MAVLINK_Rover::send_nav_controller_output()483if (!rover.control_mode->is_autopilot_mode()) {484return false;485}486distance = control_mode->get_distance_to_destination();487return true;488}489490// vehicle specific waypoint info helpers491bool Rover::get_wp_bearing_deg(float &bearing) const492{493// see GCS_MAVLINK_Rover::send_nav_controller_output()494if (!rover.control_mode->is_autopilot_mode()) {495return false;496}497bearing = control_mode->wp_bearing();498return true;499}500501// vehicle specific waypoint info helpers502bool Rover::get_wp_crosstrack_error_m(float &xtrack_error) const503{504// see GCS_MAVLINK_Rover::send_nav_controller_output()505if (!rover.control_mode->is_autopilot_mode()) {506return false;507}508xtrack_error = control_mode->crosstrack_error();509return true;510}511512513Rover rover;514AP_Vehicle& vehicle = rover;515516AP_HAL_MAIN_CALLBACKS(&rover);517518519