Skip to content

Commit

Permalink
Merge pull request #12 from peterbarker/pr/review-cleanup-patches
Browse files Browse the repository at this point in the history
Patches arising from discussion 2024-06-06
  • Loading branch information
lthall authored Jun 6, 2024
2 parents ca645b2 + 55126bb commit ec17ea7
Show file tree
Hide file tree
Showing 4 changed files with 20 additions and 16 deletions.
2 changes: 1 addition & 1 deletion ArduCopter/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -304,7 +304,7 @@
//////////////////////////////////////////////////////////////////////////////
// Ship Operations Supoort - support for landing relative to a beacon
#ifndef MODE_SHIP_OPS_ENABLED
# define MODE_SHIP_OPS_ENABLED !HAL_MINIMIZE_FEATURES && MODE_FOLLOW_ENABLED
# define MODE_SHIP_OPS_ENABLED MODE_FOLLOW_ENABLED
#endif

//////////////////////////////////////////////////////////////////////////////
Expand Down
4 changes: 3 additions & 1 deletion ArduCopter/mode.h
Original file line number Diff line number Diff line change
Expand Up @@ -1527,7 +1527,9 @@ class ModeShipOperation : public Mode {
Vector3f offset;
bool ship_takeoff;
bool pilot_correction_active;
struct {
class Ship {
public:
void reset(const Vector3f &pos_with_ofs_ned, const Vector3f &vel_ned_ms, float target_heading_deg);
Vector3p pos_ned;
Vector3f vel_ned;
Vector3f accel_ned;
Expand Down
27 changes: 13 additions & 14 deletions ArduCopter/mode_ship_ops.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -155,13 +155,7 @@ bool ModeShipOperation::init(const bool ignore_checks)
float target_heading_deg = 0.0f;
g2.follow.get_target_heading_deg(target_heading_deg);

ship.pos_ned = pos_with_ofs_ned.topostype();
ship.vel_ned = vel_ned_ms;
ship.accel_ned.zero();
ship.heading = radians(target_heading_deg);
ship.heading_rate = 0.0;
ship.heading_accel = 0.0;
ship.available = true;
ship.reset(pos_with_ofs_ned, vel_ned_ms, target_heading_deg);

offset.zero();
offset.xy() = curr_pos_neu_cm.xy() - ship.pos_ned.xy().tofloat();
Expand Down Expand Up @@ -254,6 +248,17 @@ void ModeShipOperation::set_approach_mode(ApproachMode new_approach_mode)

}

void ModeShipOperation::Ship::reset(const Vector3f &pos_with_ofs_ned, const Vector3f &vel_ned_ms, float target_heading_deg)
{
pos_ned = pos_with_ofs_ned.topostype();
vel_ned = vel_ned_ms;
accel_ned.zero();
heading = radians(target_heading_deg);
heading_rate = 0.0;
heading_accel = 0.0;
available = true;
}

void ModeShipOperation::run()
{
float yaw_cd = attitude_control->get_att_target_euler_cd().z;
Expand Down Expand Up @@ -304,13 +309,7 @@ void ModeShipOperation::run()

if (!ship.available) {
// reset ship pos, vel, accel to current value when detected.
ship.pos_ned = pos_with_ofs_ned.topostype();
ship.vel_ned = vel_ned_ms;
ship.accel_ned.zero();
ship.heading = radians(target_heading_deg);
ship.heading_rate = 0.0;
ship.heading_accel = 0.0;
ship.available = true;
ship.reset(pos_with_ofs_ned, vel_ned_ms, target_heading_deg);
}

shape_pos_vel_accel_xy(pos_with_ofs_ned.xy().topostype(), vel_ned_ms.xy(), accel_ned.xy(),
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_HAL_ChibiOS/hwdef/include/minimize_features.inc
Original file line number Diff line number Diff line change
Expand Up @@ -61,3 +61,6 @@ define AP_CAMERA_SERVO_ENABLED AP_CAMERA_ENABLED

# no SLCAN on these boards (use can-over-mavlink if required)
define AP_CAN_SLCAN_ENABLED 0

# no ship-ops on small boards:
define MODE_SHIP_OPS_ENABLED 0

0 comments on commit ec17ea7

Please sign in to comment.