forked from Archive/PX4-Autopilot
uORB delete unused vehicle_force_setpoint
This commit is contained in:
parent
d3c87c77d2
commit
b8e24b5d2f
|
@ -110,7 +110,6 @@ set(msg_files
|
|||
vehicle_command.msg
|
||||
vehicle_command_ack.msg
|
||||
vehicle_control_mode.msg
|
||||
vehicle_force_setpoint.msg
|
||||
vehicle_global_position.msg
|
||||
vehicle_gps_position.msg
|
||||
vehicle_land_detected.msg
|
||||
|
|
|
@ -84,7 +84,7 @@ msg_id_map = {
|
|||
'vehicle_command_ack': 79,
|
||||
'vehicle_command': 80,
|
||||
'vehicle_control_mode': 81,
|
||||
'vehicle_force_setpoint': 82,
|
||||
|
||||
'vehicle_global_position': 83,
|
||||
|
||||
'vehicle_gps_position': 85,
|
||||
|
|
|
@ -1,8 +0,0 @@
|
|||
# Definition of force (NED) setpoint uORB topic. Typically this can be used
|
||||
# by a position control app together with an attitude control app.
|
||||
|
||||
|
||||
float32 x # in N NED
|
||||
float32 y # in N NED
|
||||
float32 z # in N NED
|
||||
float32 yaw # right-hand rotation around downward axis (rad, equivalent to Tait-Bryan yaw)
|
|
@ -123,7 +123,6 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
|
|||
_global_vel_sp_pub(nullptr),
|
||||
_att_sp_pub(nullptr),
|
||||
_rates_sp_pub(nullptr),
|
||||
_force_sp_pub(nullptr),
|
||||
_pos_sp_triplet_pub(nullptr),
|
||||
_att_pos_mocap_pub(nullptr),
|
||||
_vision_position_pub(nullptr),
|
||||
|
@ -894,20 +893,8 @@ MavlinkReceiver::handle_message_set_position_target_local_ned(mavlink_message_t
|
|||
if (_control_mode.flag_control_offboard_enabled) {
|
||||
if (is_force_sp && offboard_control_mode.ignore_position &&
|
||||
offboard_control_mode.ignore_velocity) {
|
||||
/* The offboard setpoint is a force setpoint only, directly writing to the force
|
||||
* setpoint topic and not publishing the setpoint triplet topic */
|
||||
struct vehicle_force_setpoint_s force_sp;
|
||||
force_sp.x = set_position_target_local_ned.afx;
|
||||
force_sp.y = set_position_target_local_ned.afy;
|
||||
force_sp.z = set_position_target_local_ned.afz;
|
||||
|
||||
//XXX: yaw
|
||||
if (_force_sp_pub == nullptr) {
|
||||
_force_sp_pub = orb_advertise(ORB_ID(vehicle_force_setpoint), &force_sp);
|
||||
|
||||
} else {
|
||||
orb_publish(ORB_ID(vehicle_force_setpoint), _force_sp_pub, &force_sp);
|
||||
}
|
||||
PX4_WARN("force setpoint not supported");
|
||||
|
||||
} else {
|
||||
/* It's not a pure force setpoint: publish to setpoint triplet topic */
|
||||
|
|
|
@ -71,7 +71,6 @@
|
|||
#include <uORB/topics/debug_vect.h>
|
||||
#include <uORB/topics/airspeed.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/vehicle_force_setpoint.h>
|
||||
#include <uORB/topics/time_offset.h>
|
||||
#include <uORB/topics/distance_sensor.h>
|
||||
#include <uORB/topics/follow_target.h>
|
||||
|
@ -234,7 +233,6 @@ private:
|
|||
orb_advert_t _global_vel_sp_pub;
|
||||
orb_advert_t _att_sp_pub;
|
||||
orb_advert_t _rates_sp_pub;
|
||||
orb_advert_t _force_sp_pub;
|
||||
orb_advert_t _pos_sp_triplet_pub;
|
||||
orb_advert_t _att_pos_mocap_pub;
|
||||
orb_advert_t _vision_position_pub;
|
||||
|
|
|
@ -52,8 +52,7 @@ Mavlink::Mavlink(std::string mavlink_fcu_url) :
|
|||
_v_local_pos_sub(_n.subscribe("vehicle_local_position", 1, &Mavlink::VehicleLocalPositionCallback, this)),
|
||||
_v_att_sp_pub(_n.advertise<vehicle_attitude_setpoint>("vehicle_attitude_setpoint", 1)),
|
||||
_pos_sp_triplet_pub(_n.advertise<position_setpoint_triplet>("position_setpoint_triplet", 1)),
|
||||
_offboard_control_mode_pub(_n.advertise<offboard_control_mode>("offboard_control_mode", 1)),
|
||||
_force_sp_pub(_n.advertise<vehicle_force_setpoint>("vehicle_force_setpoint", 1))
|
||||
_offboard_control_mode_pub(_n.advertise<offboard_control_mode>("offboard_control_mode", 1))
|
||||
{
|
||||
_link = mavconn::MAVConnInterface::open_url(mavlink_fcu_url);
|
||||
_link->message_received.connect(boost::bind(&Mavlink::handle_msg, this, _1, _2, _3));
|
||||
|
@ -234,13 +233,8 @@ void Mavlink::handle_msg_set_position_target_local_ned(const mavlink_message_t *
|
|||
offboard_control_mode.ignore_velocity) {
|
||||
/* The offboard setpoint is a force setpoint only, directly writing to the force
|
||||
* setpoint topic and not publishing the setpoint triplet topic */
|
||||
vehicle_force_setpoint force_sp;
|
||||
force_sp.x = set_position_target_local_ned.afx;
|
||||
force_sp.y = set_position_target_local_ned.afy;
|
||||
force_sp.z = set_position_target_local_ned.afz;
|
||||
//XXX: yaw
|
||||
|
||||
_force_sp_pub.publish(force_sp);
|
||||
PX4_WARN("force setpoint not supported");
|
||||
|
||||
} else {
|
||||
/* It's not a pure force setpoint: publish to setpoint triplet topic */
|
||||
|
|
|
@ -48,7 +48,6 @@
|
|||
#include <px4/vehicle_local_position.h>
|
||||
#include <px4/vehicle_attitude_setpoint.h>
|
||||
#include <px4/position_setpoint_triplet.h>
|
||||
#include <px4/vehicle_force_setpoint.h>
|
||||
#include <px4/offboard_control_mode.h>
|
||||
|
||||
namespace px4
|
||||
|
|
Loading…
Reference in New Issue