Browse Source

Sub: remove setting of pos-con jerk

mission-4.1.18
Randy Mackay 7 years ago
parent
commit
2154d08185
  1. 1
      ArduSub/control_circle.cpp
  2. 1
      ArduSub/control_guided.cpp

1
ArduSub/control_circle.cpp

@ -16,7 +16,6 @@ bool Sub::circle_init() @@ -16,7 +16,6 @@ bool Sub::circle_init()
// initialize speeds and accelerations
pos_control.set_speed_xy(wp_nav.get_speed_xy());
pos_control.set_accel_xy(wp_nav.get_wp_acceleration());
pos_control.set_jerk_xy_to_default();
pos_control.set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
pos_control.set_accel_z(g.pilot_accel_z);

1
ArduSub/control_guided.cpp

@ -94,7 +94,6 @@ void Sub::guided_posvel_control_start() @@ -94,7 +94,6 @@ void Sub::guided_posvel_control_start()
// set speed and acceleration from wpnav's speed and acceleration
pos_control.set_speed_xy(wp_nav.get_speed_xy());
pos_control.set_accel_xy(wp_nav.get_wp_acceleration());
pos_control.set_jerk_xy_to_default();
const Vector3f& curr_pos = inertial_nav.get_position();
const Vector3f& curr_vel = inertial_nav.get_velocity();

Loading…
Cancel
Save