remove unused trajectory_bezier message

This commit is contained in:
Martina
2018-06-21 10:45:20 +02:00
committed by Daniel Agar
parent 5cd0da95cc
commit e7cf2c5675
4 changed files with 0 additions and 52 deletions

View File

@@ -106,7 +106,6 @@ set(msg_files
telemetry_status.msg
test_motor.msg
timesync_status.msg
trajectory_bezier.msg
trajectory_waypoint.msg
transponder_report.msg
tune_control.msg

View File

@@ -1,26 +0,0 @@
# Bezier Trajectory description. See also Mavlink TRAJECTORY msg
uint8 POINT_0 = 0
uint8 POINT_1 = 1
uint8 POINT_2 = 2
uint8 POINT_3 = 3
uint8 POINT_4 = 4
uint8 X = 0
uint8 Y = 1
uint8 Z = 2
uint8 TIME_HORIZON = 3
uint8 YAW = 4
uint8 MAV_TRAJECTORY_REPRESENTATION_BEZIER = 1
uint8 type # Type from MAV_TRAJECTORY_REPRESENTATION enum.
float32[6] point_0 # MAV_TRAJECTORY_REPRESENTATION_BEZIER, index 0-2 position wp, index 3 time horizon, index 4 yaw, index 5 yaw speed
float32[6] point_1 # MAV_TRAJECTORY_REPRESENTATION_BEZIER, index 0-2 position wp, index 3 time horizon, index 4 yaw, index 5 yaw speed
float32[6] point_2 # MAV_TRAJECTORY_REPRESENTATION_BEZIER, index 0-2 position wp, index 3 time horizon, index 4 yaw, index 5 yaw speed
float32[6] point_3 # MAV_TRAJECTORY_REPRESENTATION_BEZIER, index 0-2 position wp, index 3 time horizon, index 4 yaw, index 5 yaw speed
float32[6] point_4 # MAV_TRAJECTORY_REPRESENTATION_BEZIER, index 0-2 position wp, index 3 time horizon, index 4 yaw, index 5 yaw speed
bool[5] point_valid # States if respective point is valid
# TOPICS trajectory_bezier trajectory_bezier_desired

View File

@@ -138,7 +138,6 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_manual_pub(nullptr),
_obstacle_distance_pub(nullptr),
_trajectory_waypoint_pub(nullptr),
_trajectory_bezier_pub(nullptr),
_land_detector_pub(nullptr),
_follow_target_pub(nullptr),
_landing_target_pose_pub(nullptr),
@@ -1706,28 +1705,6 @@ MavlinkReceiver::handle_message_trajectory(mavlink_message_t *msg)
} else {
orb_publish(ORB_ID(vehicle_trajectory_waypoint), _trajectory_waypoint_pub, &trajectory_waypoint);
}
} else if (trajectory.type == trajectory_bezier_s::MAV_TRAJECTORY_REPRESENTATION_BEZIER) {
struct trajectory_bezier_s trajectory_bezier = {};
trajectory_bezier.timestamp = hrt_absolute_time();
trajectory_bezier.type = trajectory.type;
memcpy(trajectory_bezier.point_0, trajectory.point_1, sizeof(trajectory_bezier.point_0));
memcpy(trajectory_bezier.point_1, trajectory.point_2, sizeof(trajectory_bezier.point_1));
memcpy(trajectory_bezier.point_2, trajectory.point_3, sizeof(trajectory_bezier.point_2));
memcpy(trajectory_bezier.point_3, trajectory.point_4, sizeof(trajectory_bezier.point_3));
memcpy(trajectory_bezier.point_4, trajectory.point_5, sizeof(trajectory_bezier.point_4));
memcpy(trajectory_bezier.point_valid, trajectory.point_valid, sizeof(trajectory_bezier.point_valid));
if (_trajectory_bezier_pub == nullptr) {
_trajectory_bezier_pub = orb_advertise(ORB_ID(trajectory_bezier), &trajectory_bezier);
} else {
orb_publish(ORB_ID(trajectory_bezier), _trajectory_bezier_pub, &trajectory_bezier);
}
}
}

View File

@@ -67,7 +67,6 @@
#include <uORB/topics/position_setpoint_triplet.h>
#include <uORB/topics/rc_channels.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/trajectory_bezier.h>
#include <uORB/topics/vehicle_trajectory_waypoint.h>
#include <uORB/topics/transponder_report.h>
#include <uORB/topics/telemetry_status.h>
@@ -236,7 +235,6 @@ private:
orb_advert_t _manual_pub;
orb_advert_t _obstacle_distance_pub;
orb_advert_t _trajectory_waypoint_pub;
orb_advert_t _trajectory_bezier_pub;
orb_advert_t _land_detector_pub;
orb_advert_t _follow_target_pub;
orb_advert_t _landing_target_pose_pub;