Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enabled sending waypoints to ardupilot for copter and rover #26362

Merged
merged 3 commits into from
May 2, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 9 additions & 0 deletions ArduCopter/AP_ExternalControl_Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,15 @@ bool AP_ExternalControl_Copter::set_linear_velocity_and_yaw_rate(const Vector3f
return true;
}

bool AP_ExternalControl_Copter::set_global_position(const Location& loc)
{
// Check if copter is ready for external control and returns false if it is not.
if (!ready_for_external_control()) {
return false;
}
return copter.set_target_location(loc);
}

bool AP_ExternalControl_Copter::ready_for_external_control()
{
return copter.flightmode->in_guided_mode() && copter.motors->armed();
Expand Down
8 changes: 7 additions & 1 deletion ArduCopter/AP_ExternalControl_Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,20 @@

#if AP_EXTERNAL_CONTROL_ENABLED

class AP_ExternalControl_Copter : public AP_ExternalControl {
class AP_ExternalControl_Copter : public AP_ExternalControl
{
public:
/*
Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw.
Velocity is in earth frame, NED [m/s].
Yaw is in earth frame, NED [rad/s].
*/
bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads) override WARN_IF_UNUSED;

/*
Sets the target global position for a loiter point.
*/
bool set_global_position(const Location& loc) override WARN_IF_UNUSED;
private:
/*
Return true if Copter is ready to handle external control data.
Expand Down
27 changes: 16 additions & 11 deletions ArduCopter/Copter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,32 +272,37 @@ void Copter::get_scheduler_tasks(const AP_Scheduler::Task *&tasks,

constexpr int8_t Copter::_failsafe_priorities[7];

#if AP_SCRIPTING_ENABLED

#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
// start takeoff to given altitude (for use by scripting)
bool Copter::start_takeoff(float alt)
// set target location (for use by external control and scripting)
bool Copter::set_target_location(const Location& target_loc)
Ryanf55 marked this conversation as resolved.
Show resolved Hide resolved
{
// exit if vehicle is not in Guided mode or Auto-Guided mode
if (!flightmode->in_guided_mode()) {
return false;
}

if (mode_guided.do_user_takeoff_start(alt * 100.0f)) {
copter.set_auto_armed(true);
return true;
}
return false;
return mode_guided.set_destination(target_loc);
}
#endif //MODE_GUIDED_ENABLED == ENABLED
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED

// set target location (for use by scripting)
bool Copter::set_target_location(const Location& target_loc)
#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
// start takeoff to given altitude (for use by scripting)
bool Copter::start_takeoff(float alt)
{
// exit if vehicle is not in Guided mode or Auto-Guided mode
if (!flightmode->in_guided_mode()) {
return false;
}

return mode_guided.set_destination(target_loc);
if (mode_guided.do_user_takeoff_start(alt * 100.0f)) {
rmackay9 marked this conversation as resolved.
Show resolved Hide resolved
copter.set_auto_armed(true);
return true;
}
return false;
}

// set target position (for use by scripting)
Expand Down
7 changes: 6 additions & 1 deletion ArduCopter/Copter.h
Original file line number Diff line number Diff line change
Expand Up @@ -666,10 +666,15 @@ class Copter : public AP_Vehicle {
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
uint8_t &task_count,
uint32_t &log_bit) override;
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
bool set_target_location(const Location& target_loc) override;
#endif // MODE_GUIDED_ENABLED == ENABLED
#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED

#if AP_SCRIPTING_ENABLED
#if MODE_GUIDED_ENABLED == ENABLED
bool start_takeoff(float alt) override;
bool set_target_location(const Location& target_loc) override;
bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) override;
bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) override;
bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) override;
Expand Down
6 changes: 6 additions & 0 deletions Rover/AP_ExternalControl_Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,12 @@ bool AP_ExternalControl_Rover::set_linear_velocity_and_yaw_rate(const Vector3f &
return true;
}

bool AP_ExternalControl_Rover::set_global_position(const Location& loc)
{
// set_target_location only checks if the rover is in guided mode or not
return rover.set_target_location(loc);
}

bool AP_ExternalControl_Rover::ready_for_external_control()
{
return rover.control_mode->in_guided_mode() && rover.arming.is_armed();
Expand Down
9 changes: 8 additions & 1 deletion Rover/AP_ExternalControl_Rover.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,14 +7,21 @@

#if AP_EXTERNAL_CONTROL_ENABLED

class AP_ExternalControl_Rover : public AP_ExternalControl {
class AP_ExternalControl_Rover : public AP_ExternalControl
{
public:
/*
Set linear velocity and yaw rate. Pass NaN for yaw_rate_rads to not control yaw.
Velocity is in earth frame, NED [m/s].
Yaw is in earth frame, NED [rad/s].
*/
bool set_linear_velocity_and_yaw_rate(const Vector3f &linear_velocity, float yaw_rate_rads)override WARN_IF_UNUSED;

/*
Sets the global position for loiter point
*/
bool set_global_position(const Location& loc) override WARN_IF_UNUSED;

private:
/*
Return true if Rover is ready to handle external control data.
Expand Down
6 changes: 4 additions & 2 deletions Rover/Rover.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,8 +157,8 @@ Rover::Rover(void) :
{
}

#if AP_SCRIPTING_ENABLED
// set target location (for use by scripting)
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
// set target location (for use by external control and scripting)
bool Rover::set_target_location(const Location& target_loc)
{
// exit if vehicle is not in Guided mode or Auto-Guided mode
Expand All @@ -168,7 +168,9 @@ bool Rover::set_target_location(const Location& target_loc)

return mode_guided.set_desired_location(target_loc);
}
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED

#if AP_SCRIPTING_ENABLED
// set target velocity (for use by scripting)
bool Rover::set_target_velocity_NED(const Vector3f& vel_ned)
{
Expand Down
5 changes: 4 additions & 1 deletion Rover/Rover.h
Original file line number Diff line number Diff line change
Expand Up @@ -269,8 +269,11 @@ class Rover : public AP_Vehicle {
cruise_learn_t cruise_learn;

// Rover.cpp
#if AP_SCRIPTING_ENABLED
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
bool set_target_location(const Location& target_loc) override;
#endif

#if AP_SCRIPTING_ENABLED
bool set_target_velocity_NED(const Vector3f& vel_ned) override;
bool set_steering_and_throttle(float steering, float throttle) override;
bool get_steering_and_throttle(float& steering, float& throttle) override;
Expand Down
4 changes: 4 additions & 0 deletions Tools/scripts/run_astyle.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,12 @@ def __init__(self, *, dry_run=DRY_RUN_DEFAULT):
]
self.files_to_check = [
pathlib.Path(s) for s in [
'ArduCopter/AP_ExternalControl_Copter.cpp',
'ArduCopter/AP_ExternalControl_Copter.h',
'libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.cpp',
'libraries/AP_ExternalAHRS/AP_ExternalAHRS_MicroStrain7.h',
'Rover/AP_ExternalControl_Rover.cpp',
'Rover/AP_ExternalControl_Rover.h',
]
]
self.dry_run = dry_run
Expand Down
Loading