Browse Source

Rover: move rally to g2

master
Randy Mackay 7 years ago
parent
commit
f0ad8760e2
  1. 2
      APMrover2/GCS_Mavlink.cpp
  2. 15
      APMrover2/Parameters.cpp
  3. 5
      APMrover2/Parameters.h
  4. 3
      APMrover2/Rover.h
  5. 2
      APMrover2/mode_rtl.cpp

2
APMrover2/GCS_Mavlink.cpp

@ -1308,7 +1308,7 @@ AP_Mission *GCS_MAVLINK_Rover::get_mission() @@ -1308,7 +1308,7 @@ AP_Mission *GCS_MAVLINK_Rover::get_mission()
AP_Rally *GCS_MAVLINK_Rover::get_rally() const
{
#if AC_RALLY == ENABLED
return &rover.rally;
return &rover.g2.rally;
#else
return nullptr;
#endif

15
APMrover2/Parameters.cpp

@ -356,12 +356,6 @@ const AP_Param::Info Rover::var_info[] = { @@ -356,12 +356,6 @@ const AP_Param::Info Rover::var_info[] = {
GOBJECT(camera_mount, "MNT", AP_Mount),
#endif
#if AC_RALLY == ENABLED
// @Group: RALLY_
// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
GOBJECT(rally, "RALLY_", AP_Rally_Rover),
#endif
// @Group: ARMING_
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
GOBJECT(arming, "ARMING_", AP_Arming),
@ -591,6 +585,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { @@ -591,6 +585,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: ../libraries/AP_WheelEncoder/AP_WheelRateControl.cpp
AP_SUBGROUPINFO(wheel_rate_control, "WRC", 27, ParametersG2, AP_WheelRateControl),
#if AC_RALLY == ENABLED
// @Group: RALLY_
// @Path: AP_Rally.cpp,../libraries/AP_Rally/AP_Rally.cpp
AP_SUBGROUPINFO(rally, "RALLY_", 28, ParametersG2, AP_Rally_Rover),
#endif
AP_GROUPEND
};
@ -621,7 +621,8 @@ ParametersG2::ParametersG2(void) @@ -621,7 +621,8 @@ ParametersG2::ParametersG2(void)
fence(rover.ahrs),
proximity(rover.serial_manager),
avoid(rover.ahrs, fence, rover.g2.proximity, &rover.g2.beacon),
follow()
follow(),
rally(rover.ahrs)
{
AP_Param::setup_object_defaults(this, var_info);
}

5
APMrover2/Parameters.h

@ -4,6 +4,7 @@ @@ -4,6 +4,7 @@
#include "RC_Channel.h"
#include "AC_Sprayer/AC_Sprayer.h"
#include "AP_Rally.h"
// Global parameter class.
//
@ -54,7 +55,6 @@ public: @@ -54,7 +55,6 @@ public:
k_param_serial0_baud, // deprecated, can be deleted
k_param_serial1_baud, // deprecated, can be deleted
k_param_serial2_baud, // deprecated, can be deleted
k_param_rally,
// 97: RSSI
k_param_rssi = 97,
@ -364,6 +364,9 @@ public: @@ -364,6 +364,9 @@ public:
// Sprayer
AC_Sprayer sprayer;
// Rally point library
AP_Rally_Rover rally;
};
extern const AP_Param::Info var_info[];

3
APMrover2/Rover.h

@ -242,9 +242,6 @@ private: @@ -242,9 +242,6 @@ private:
AP_Mount camera_mount{ahrs, current_loc};
#endif
// Rally library
AP_Rally_Rover rally{ahrs};
// true if initialisation has completed
bool initialised;

2
APMrover2/mode_rtl.cpp

@ -10,7 +10,7 @@ bool ModeRTL::_enter() @@ -10,7 +10,7 @@ bool ModeRTL::_enter()
// initialise waypoint speed
set_desired_speed_to_default(true);
return_target = rover.rally.calc_best_rally_or_home_location(rover.current_loc, ahrs.get_home().alt);
return_target = rover.g2.rally.calc_best_rally_or_home_location(rover.current_loc, ahrs.get_home().alt);
// set destination
set_desired_location(return_target);
return true;

Loading…
Cancel
Save