Path: blob/master/Rover/AP_ExternalControl_Rover.cpp
9411 views
/*1external control library for rover2*/345#include "AP_ExternalControl_Rover.h"6#if AP_EXTERNAL_CONTROL_ENABLED78#include "Rover.h"910/*11set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw12velocity is in earth frame, NED, m/s13*/14bool AP_ExternalControl_Rover::set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads)15{16if (!ready_for_external_control()) {17return false;18}1920// rover is commanded in body-frame using FRD convention21auto &ahrs = AP::ahrs();22Vector3f linear_velocity_body = ahrs.earth_to_body(linear_velocity);2324const float target_speed = linear_velocity_body.x;25const float turn_rate_cds = isnan(yaw_rate_rads)? 0: degrees(yaw_rate_rads)*100;2627rover.mode_guided.set_desired_turn_rate_and_speed(turn_rate_cds, target_speed);28return true;29}3031bool AP_ExternalControl_Rover::set_global_position(const Location& loc)32{33// set_target_location only checks if the rover is in guided mode or not34return rover.set_target_location(loc);35}3637bool AP_ExternalControl_Rover::ready_for_external_control()38{39return rover.control_mode->in_guided_mode() && rover.arming.is_armed();40}4142#endif // AP_EXTERNAL_CONTROL_ENABLED434445