mirror of https://github.com/ArduPilot/ardupilot
APMrover 2.20b: minor update for HIL mode with the new lib
Signed-off-by: Jean-Louis Naudin <jlnaudin@gmail.com>
This commit is contained in:
parent
cd0411ba33
commit
94ccdea145
|
@ -61,7 +61,7 @@ the when the rover approach the wp, it slow down to 4 m/s (TRIM_ARSPD_CM)...
|
|||
This feature works only if the ROV_AWPR_NAV is set to 0
|
||||
*/
|
||||
|
||||
#define BOOSTER 1 // booster factor x1 = 1 or x2 = 2
|
||||
#define BOOSTER 2 // booster factor x1 = 1 or x2 = 2
|
||||
#define AUTO_WP_RADIUS DISABLED
|
||||
#define AIRSPEED_CRUISE 4 // 4m/s
|
||||
#define THROTTLE_SLEW_LIMIT 2 // set to 2 for a smooth acceleration by 0.2 step
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
||||
|
||||
#define THISFIRMWARE "APMrover v2.20a JL NAUDIN" //New version of the APMrover for the APM v1 or APM v2 and magnetometer + SONAR
|
||||
#define THISFIRMWARE "APMrover v2.20b JL NAUDIN" //New version of the APMrover for the APM v1 or APM v2 and magnetometer + SONAR
|
||||
|
||||
// This is the APMrover firmware derived from the Arduplane v2.32 by Jean-Louis Naudin (JLN)
|
||||
/*
|
||||
|
@ -14,11 +14,12 @@ modify it under the terms of the GNU Lesser General Public
|
|||
License as published by the Free Software Foundation; either
|
||||
version 2.1 of the License, or (at your option) any later version.
|
||||
//
|
||||
// JLN updates: last update 2012-06-13
|
||||
// JLN updates: last update 2012-06-21
|
||||
// DOLIST:
|
||||
//-------------------------------------------------------------------------------------------------------------------------
|
||||
// Dev Startup : 2012-04-21
|
||||
//
|
||||
// 2012-06-21: Update for HIL mode with mavlink 1.0 (new lib)
|
||||
// 2012-06-13: use RangeFinder optical SharpGP2Y instead of ultrasonic sonar
|
||||
// 2012-06-13: added Test sonar
|
||||
// 2012-05-17: added speed_boost during straight line
|
||||
|
|
|
@ -378,6 +378,8 @@ static void NOINLINE send_servo_out(mavlink_channel_t chan)
|
|||
int thr_out = constrain((g.channel_throttle.servo_out *2) - 100, -100, 100); // throttle set from -100 to 100
|
||||
mavlink_msg_rc_channels_scaled_send(
|
||||
chan,
|
||||
millis(),
|
||||
0, // port 0
|
||||
g.channel_roll.servo_out,
|
||||
g.channel_pitch.servo_out,
|
||||
100 * thr_out,
|
||||
|
|
Loading…
Reference in New Issue