Browse Source

Egg_drop has a 0..100 range

mission-4.1.18
Amilcar Lucas 14 years ago
parent
commit
7e0bff9cbe
  1. 4
      ArduPlane/WP_activity.pde

4
ArduPlane/WP_activity.pde

@ -32,10 +32,10 @@ void egg_waypoint() @@ -32,10 +32,10 @@ void egg_waypoint()
if(g.waypoint_index == 3){
if(wp_distance < egg_dist){
g_rc_function[RC_Channel_aux::k_egg_drop]->servo_out = 1500 + (-45*10.31);
g_rc_function[RC_Channel_aux::k_egg_drop]->servo_out = 100;
}
}else{
g_rc_function[RC_Channel_aux::k_egg_drop]->servo_out = 1500 + (45*10.31);
g_rc_function[RC_Channel_aux::k_egg_drop]->servo_out = 0;
}
}
}

Loading…
Cancel
Save