msg/geofence_update.msg: remove this topic

We'll use dataman to check for geofence data updates.
This commit is contained in:
Beat Küng
2017-05-18 12:02:15 +02:00
committed by Lorenz Meier
parent 72501df88e
commit 3d3e6428c2
6 changed files with 0 additions and 26 deletions
-1
View File
@@ -59,7 +59,6 @@ set(msg_file_names
follow_target.msg
fw_pos_ctrl_status.msg
geofence_result.msg
geofence_update.msg
gps_dump.msg
gps_inject_data.msg
hil_sensor.msg
-4
View File
@@ -1,4 +0,0 @@
# This message is used to notify the system about a geofence update (dataman
# storage)
uint32 dummy # unused
-6
View File
@@ -51,7 +51,6 @@
#include <px4_defines.h>
#include <navigator/navigation.h>
#include <uORB/topics/geofence_update.h>
#include <uORB/topics/mission.h>
#include <uORB/topics/mission_result.h>
@@ -88,7 +87,6 @@ MavlinkMissionManager::MavlinkMissionManager(Mavlink *mavlink) :
_offboard_mission_sub(-1),
_mission_result_sub(-1),
_offboard_mission_pub(nullptr),
_geofence_update_pub(nullptr),
_slow_rate_limiter(100 * 1000), // Rate limit sending of the current WP sequence to 10 Hz
_verbose(mavlink->verbose()),
_mavlink(mavlink)
@@ -103,7 +101,6 @@ MavlinkMissionManager::~MavlinkMissionManager()
{
orb_unsubscribe(_mission_result_sub);
orb_unadvertise(_offboard_mission_pub);
orb_unadvertise(_geofence_update_pub);
}
void
@@ -214,9 +211,6 @@ MavlinkMissionManager::update_geofence_count(unsigned count)
if (res == sizeof(mission_stats_entry_s)) {
_count[(uint8_t)MAV_MISSION_TYPE_FENCE] = count;
geofence_update_s geofence_update{};
orb_publish_auto(ORB_ID(geofence_update), &_geofence_update_pub, &geofence_update, nullptr, ORB_PRIO_DEFAULT);
} else {
PX4_ERR("WPM: can't save mission state");
-1
View File
@@ -126,7 +126,6 @@ private:
int _offboard_mission_sub;
int _mission_result_sub;
orb_advert_t _offboard_mission_pub;
orb_advert_t _geofence_update_pub;
MavlinkRateLimiter _slow_rate_limiter;
-1
View File
@@ -236,7 +236,6 @@ private:
int _param_update_sub{-1}; /**< param update subscription */
int _sensor_combined_sub{-1}; /**< sensor combined subscription */
int _vehicle_command_sub{-1}; /**< vehicle commands (onboard and offboard) */
int _geofence_update_sub{-1}; /**< geofence updates */
int _vstatus_sub{-1}; /**< vehicle status subscription */
orb_advert_t _att_sp_pub{nullptr};
-13
View File
@@ -65,7 +65,6 @@
#include <arch/board/board.h>
#include <uORB/uORB.h>
#include <uORB/topics/geofence_update.h>
#include <uORB/topics/fw_pos_ctrl_status.h>
#include <uORB/topics/home_position.h>
#include <uORB/topics/mission.h>
@@ -252,7 +251,6 @@ Navigator::task_main()
_offboard_mission_sub = orb_subscribe(ORB_ID(offboard_mission));
_param_update_sub = orb_subscribe(ORB_ID(parameter_update));
_vehicle_command_sub = orb_subscribe(ORB_ID(vehicle_command));
_geofence_update_sub = orb_subscribe(ORB_ID(geofence_update));
/* copy all topics first time */
vehicle_status_update();
@@ -346,15 +344,6 @@ Navigator::task_main()
params_update();
}
/* geofence updated */
orb_check(_geofence_update_sub, &updated);
if (updated) {
geofence_update_s geofence_update;
orb_copy(ORB_ID(geofence_update), _geofence_update_sub, &geofence_update);
_geofence.updateFence();
}
/* vehicle status updated */
orb_check(_vstatus_sub, &updated);
@@ -706,8 +695,6 @@ Navigator::task_main()
_param_update_sub = -1;
orb_unsubscribe(_vehicle_command_sub);
_vehicle_command_sub = -1;
orb_unsubscribe(_geofence_update_sub);
_geofence_update_sub = -1;
PX4_INFO("exiting");