Browse Source

Rover: move AIS to vehicle

This reverts most of commit e86665a989.
apm_2208
Iampete1 4 years ago committed by Andrew Tridgell
parent
commit
7fd157acb4
  1. 7
      Rover/GCS_Mavlink.cpp
  2. 17
      Rover/Parameters.cpp
  3. 5
      Rover/Parameters.h
  4. 3
      Rover/Rover.cpp
  5. 4
      Rover/system.cpp
  6. 1
      Rover/wscript

7
Rover/GCS_Mavlink.cpp

@ -388,13 +388,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id) @@ -388,13 +388,6 @@ bool GCS_MAVLINK_Rover::try_send_message(enum ap_message id)
break;
}
case MSG_AIS_VESSEL: {
#if HAL_AIS_ENABLED
rover.g2.ais.send(chan);
#endif
break;
}
default:
return GCS_MAVLINK::try_send_message(id);
}

17
Rover/Parameters.cpp

@ -650,12 +650,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { @@ -650,12 +650,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(torqeedo, "TRQD_", 49, ParametersG2, AP_Torqeedo),
#endif
#if HAL_AIS_ENABLED
// @Group: AIS_
// @Path: ../libraries/AP_AIS/AP_AIS.cpp
AP_SUBGROUPINFO(ais, "AIS_", 50, ParametersG2, AP_AIS),
#endif
// @Group: PSC
// @Path: ../libraries/APM_Control/AR_PosControl.cpp
AP_SUBGROUPINFO(pos_control, "PSC", 51, ParametersG2, AR_PosControl),
@ -852,16 +846,23 @@ void Rover::load_parameters(void) @@ -852,16 +846,23 @@ void Rover::load_parameters(void)
AP_BoardConfig::BOARD_SAFETY_OPTION_BUTTON_ACTIVE_ARMED);
#endif
// PARAMETER_CONVERSION - Added: JAN-2022
#if AP_AIRSPEED_ENABLED
#if AP_AIRSPEED_ENABLED | AP_AIS_ENABLED
// Find G2's Top Level Key
AP_Param::ConversionInfo info;
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
return;
}
#endif
// PARAMETER_CONVERSION - Added: JAN-2022
#if AP_AIRSPEED_ENABLED
const uint16_t old_index = 37; // Old parameter index in the tree
const uint16_t old_top_element = 4069; // Old group element in the tree for the first subgroup element
AP_Param::convert_class(info.old_key, &airspeed, airspeed.var_info, old_index, old_top_element, false);
#endif
// PARAMETER_CONVERSION - Added: MAR-2022
#if AP_AIS_ENABLED
AP_Param::convert_class(info.old_key, &ais, ais.var_info, 50, 114, false);
#endif
}

5
Rover/Parameters.h

@ -415,11 +415,6 @@ public: @@ -415,11 +415,6 @@ public:
AP_Torqeedo torqeedo;
#endif
#if HAL_AIS_ENABLED
// Automatic Identification System - for tracking sea-going vehicles
AP_AIS ais;
#endif
// position controller
AR_PosControl pos_control;

3
Rover/Rover.cpp

@ -130,9 +130,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = { @@ -130,9 +130,6 @@ const AP_Scheduler::Task Rover::scheduler_tasks[] = {
#if ADVANCED_FAILSAFE == ENABLED
SCHED_TASK(afs_fs_check, 10, 200, 129),
#endif
#if HAL_AIS_ENABLED
SCHED_TASK_CLASS(AP_AIS, &rover.g2.ais, update, 5, 100, 135),
#endif
};

4
Rover/system.cpp

@ -58,10 +58,6 @@ void Rover::init_ardupilot() @@ -58,10 +58,6 @@ void Rover::init_ardupilot()
log_init();
#endif
#if HAL_AIS_ENABLED
g2.ais.init();
#endif
// initialise compass
AP::compass().set_log_bit(MASK_LOG_COMPASS);
AP::compass().init();

1
Rover/wscript

@ -26,7 +26,6 @@ def build(bld): @@ -26,7 +26,6 @@ def build(bld):
'AP_WindVane',
'AR_Motors',
'AP_Torqeedo',
'AP_AIS',
],
)

Loading…
Cancel
Save