mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
delete vehicle_global_velocity_setpoint
This commit is contained in:
parent
fc860140f1
commit
f947205cbe
@ -115,7 +115,6 @@ set(msg_file_names
|
||||
vehicle_control_mode.msg
|
||||
vehicle_force_setpoint.msg
|
||||
vehicle_global_position.msg
|
||||
vehicle_global_velocity_setpoint.msg
|
||||
vehicle_gps_position.msg
|
||||
vehicle_land_detected.msg
|
||||
vehicle_local_position.msg
|
||||
|
||||
@ -1,4 +0,0 @@
|
||||
# Velocity setpoint in NED frame
|
||||
float32 vx # in m/s NED
|
||||
float32 vy # in m/s NED
|
||||
float32 vz # in m/s NED
|
||||
@ -58,12 +58,10 @@ MulticopterPositionControlMultiplatform::MulticopterPositionControlMultiplatform
|
||||
/* publications */
|
||||
_att_sp_pub(nullptr),
|
||||
_local_pos_sp_pub(nullptr),
|
||||
_global_vel_sp_pub(nullptr),
|
||||
|
||||
/* outgoing messages */
|
||||
_att_sp_msg(),
|
||||
_local_pos_sp_msg(),
|
||||
_global_vel_sp_msg(),
|
||||
|
||||
_n(_appState),
|
||||
|
||||
@ -116,8 +114,6 @@ _R()
|
||||
_pos_sp_triplet = _n.subscribe<px4_position_setpoint_triplet>
|
||||
(&MulticopterPositionControlMultiplatform::handle_position_setpoint_triplet, this, 0);
|
||||
_local_pos_sp = _n.subscribe<px4_vehicle_local_position_setpoint>(0);
|
||||
_global_vel_sp = _n.subscribe<px4_vehicle_global_velocity_setpoint>(0);
|
||||
|
||||
|
||||
_params.pos_p.zero();
|
||||
_params.vel_p.zero();
|
||||
@ -700,18 +696,6 @@ void MulticopterPositionControlMultiplatform::handle_vehicle_attitude(const px4
|
||||
_vel_sp(2) = _params.land_speed;
|
||||
}
|
||||
|
||||
_global_vel_sp_msg.data().vx = _vel_sp(0);
|
||||
_global_vel_sp_msg.data().vy = _vel_sp(1);
|
||||
_global_vel_sp_msg.data().vz = _vel_sp(2);
|
||||
|
||||
/* publish velocity setpoint */
|
||||
if (_global_vel_sp_pub != nullptr) {
|
||||
_global_vel_sp_pub->publish(_global_vel_sp_msg);
|
||||
|
||||
} else {
|
||||
_global_vel_sp_pub = _n.advertise<px4_vehicle_global_velocity_setpoint>();
|
||||
}
|
||||
|
||||
if (_control_mode->data().flag_control_climb_rate_enabled || _control_mode->data().flag_control_velocity_enabled) {
|
||||
/* reset integrals if needed */
|
||||
if (_control_mode->data().flag_control_climb_rate_enabled) {
|
||||
|
||||
@ -88,9 +88,6 @@ protected:
|
||||
|
||||
Publisher<px4_vehicle_attitude_setpoint> *_att_sp_pub; /**< attitude setpoint publication */
|
||||
Publisher<px4_vehicle_local_position_setpoint> *_local_pos_sp_pub; /**< vehicle local position setpoint publication */
|
||||
Publisher<px4_vehicle_global_velocity_setpoint>
|
||||
*_global_vel_sp_pub; /**< vehicle global velocity setpoint publication */
|
||||
|
||||
|
||||
Subscriber<px4_vehicle_attitude> *_att; /**< vehicle attitude */
|
||||
Subscriber<px4_vehicle_control_mode> *_control_mode; /**< vehicle control mode */
|
||||
@ -100,11 +97,9 @@ protected:
|
||||
Subscriber<px4_vehicle_local_position> *_local_pos; /**< local position */
|
||||
Subscriber<px4_position_setpoint_triplet> *_pos_sp_triplet; /**< local position */
|
||||
Subscriber<px4_vehicle_local_position_setpoint> *_local_pos_sp; /**< local position */
|
||||
Subscriber<px4_vehicle_global_velocity_setpoint> *_global_vel_sp; /**< local position */
|
||||
|
||||
px4_vehicle_attitude_setpoint _att_sp_msg;
|
||||
px4_vehicle_local_position_setpoint _local_pos_sp_msg;
|
||||
px4_vehicle_global_velocity_setpoint _global_vel_sp_msg;
|
||||
|
||||
px4::NodeHandle _n;
|
||||
|
||||
|
||||
@ -576,7 +576,6 @@ void Logger::add_default_topics()
|
||||
add_topic("vehicle_local_position", 100);
|
||||
add_topic("vehicle_local_position_setpoint", 100);
|
||||
add_topic("vehicle_global_position", 200);
|
||||
add_topic("vehicle_global_velocity_setpoint", 200);
|
||||
add_topic("vehicle_vision_position");
|
||||
add_topic("vehicle_vision_attitude");
|
||||
add_topic("battery_status", 300);
|
||||
|
||||
@ -56,7 +56,6 @@
|
||||
#include <uORB/topics/offboard_control_mode.h>
|
||||
#include <uORB/topics/vehicle_command.h>
|
||||
#include <uORB/topics/vehicle_local_position_setpoint.h>
|
||||
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/att_pos_mocap.h>
|
||||
#include <uORB/topics/vehicle_attitude_setpoint.h>
|
||||
|
||||
@ -61,7 +61,6 @@
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
#include <uORB/topics/position_setpoint_triplet.h>
|
||||
#include <uORB/topics/vehicle_control_mode.h>
|
||||
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
|
||||
#include <uORB/topics/vehicle_land_detected.h>
|
||||
#include <uORB/topics/vehicle_local_position.h>
|
||||
#include <uORB/topics/vehicle_local_position_setpoint.h>
|
||||
@ -121,7 +120,6 @@ private:
|
||||
int _home_pos_sub; /**< home position */
|
||||
orb_advert_t _att_sp_pub; /**< attitude setpoint publication */
|
||||
orb_advert_t _local_pos_sp_pub; /**< vehicle local position setpoint publication */
|
||||
orb_advert_t _global_vel_sp_pub; /**< vehicle global velocity setpoint publication */
|
||||
|
||||
orb_id_t _attitude_setpoint_id;
|
||||
|
||||
@ -134,7 +132,6 @@ private:
|
||||
struct vehicle_local_position_s _local_pos; /**< vehicle local position */
|
||||
struct position_setpoint_triplet_s _pos_sp_triplet; /**< vehicle global position setpoint triplet */
|
||||
struct vehicle_local_position_setpoint_s _local_pos_sp; /**< vehicle local position setpoint */
|
||||
struct vehicle_global_velocity_setpoint_s _global_vel_sp; /**< vehicle global velocity setpoint */
|
||||
struct home_position_s _home_pos; /**< home position */
|
||||
|
||||
control::BlockParamFloat _manual_thr_min; /**< minimal throttle output when flying in manual mode */
|
||||
@ -394,7 +391,6 @@ MulticopterPositionControl::MulticopterPositionControl() :
|
||||
/* publications */
|
||||
_att_sp_pub(nullptr),
|
||||
_local_pos_sp_pub(nullptr),
|
||||
_global_vel_sp_pub(nullptr),
|
||||
_attitude_setpoint_id(nullptr),
|
||||
_vehicle_status{},
|
||||
_vehicle_land_detected{},
|
||||
@ -405,7 +401,6 @@ MulticopterPositionControl::MulticopterPositionControl() :
|
||||
_local_pos{},
|
||||
_pos_sp_triplet{},
|
||||
_local_pos_sp{},
|
||||
_global_vel_sp{},
|
||||
_home_pos{},
|
||||
_manual_thr_min(this, "MANTHR_MIN"),
|
||||
_manual_thr_max(this, "MANTHR_MAX"),
|
||||
@ -1782,19 +1777,6 @@ MulticopterPositionControl::calculate_velocity_setpoint(float dt)
|
||||
/* limit vertical velocity to the current ramp value */
|
||||
_vel_sp(2) = math::max(_vel_sp(2), -_takeoff_vel_limit);
|
||||
}
|
||||
|
||||
/* publish velocity setpoint */
|
||||
_global_vel_sp.timestamp = hrt_absolute_time();
|
||||
_global_vel_sp.vx = _vel_sp(0);
|
||||
_global_vel_sp.vy = _vel_sp(1);
|
||||
_global_vel_sp.vz = _vel_sp(2);
|
||||
|
||||
if (_global_vel_sp_pub != nullptr) {
|
||||
orb_publish(ORB_ID(vehicle_global_velocity_setpoint), _global_vel_sp_pub, &_global_vel_sp);
|
||||
|
||||
} else {
|
||||
_global_vel_sp_pub = orb_advertise(ORB_ID(vehicle_global_velocity_setpoint), &_global_vel_sp);
|
||||
}
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@ -79,7 +79,6 @@
|
||||
#include <uORB/topics/vehicle_gps_position.h>
|
||||
#include <uORB/topics/satellite_info.h>
|
||||
#include <uORB/topics/att_pos_mocap.h>
|
||||
#include <uORB/topics/vehicle_global_velocity_setpoint.h>
|
||||
#include <uORB/topics/optical_flow.h>
|
||||
#include <uORB/topics/battery_status.h>
|
||||
#include <uORB/topics/differential_pressure.h>
|
||||
@ -1186,7 +1185,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
struct differential_pressure_s diff_pres;
|
||||
struct airspeed_s airspeed;
|
||||
struct esc_status_s esc;
|
||||
struct vehicle_global_velocity_setpoint_s global_vel_sp;
|
||||
struct battery_status_s battery;
|
||||
struct telemetry_status_s telemetry;
|
||||
struct distance_sensor_s distance_sensor;
|
||||
@ -1302,7 +1300,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
int rc_sub;
|
||||
int airspeed_sub;
|
||||
int esc_sub;
|
||||
int global_vel_sp_sub;
|
||||
int battery_sub;
|
||||
int telemetry_subs[ORB_MULTI_MAX_INSTANCES];
|
||||
int distance_sensor_sub;
|
||||
@ -1348,7 +1345,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
subs.rc_sub = -1;
|
||||
subs.airspeed_sub = -1;
|
||||
subs.esc_sub = -1;
|
||||
subs.global_vel_sp_sub = -1;
|
||||
subs.battery_sub = -1;
|
||||
subs.distance_sensor_sub = -1;
|
||||
subs.estimator_status_sub = -1;
|
||||
@ -2069,15 +2065,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
}
|
||||
}
|
||||
|
||||
/* --- GLOBAL VELOCITY SETPOINT --- */
|
||||
if (copy_if_updated(ORB_ID(vehicle_global_velocity_setpoint), &subs.global_vel_sp_sub, &buf.global_vel_sp)) {
|
||||
log_msg.msg_type = LOG_GVSP_MSG;
|
||||
log_msg.body.log_GVSP.vx = buf.global_vel_sp.vx;
|
||||
log_msg.body.log_GVSP.vy = buf.global_vel_sp.vy;
|
||||
log_msg.body.log_GVSP.vz = buf.global_vel_sp.vz;
|
||||
LOGBUFFER_WRITE_AND_COUNT(GVSP);
|
||||
}
|
||||
|
||||
/* --- BATTERY --- */
|
||||
if (copy_if_updated(ORB_ID(battery_status), &subs.battery_sub, &buf.battery)) {
|
||||
log_msg.msg_type = LOG_BATT_MSG;
|
||||
|
||||
@ -62,7 +62,6 @@
|
||||
#include <px4_parameter_update.h>
|
||||
#include <px4_vehicle_status.h>
|
||||
#include <px4_vehicle_local_position_setpoint.h>
|
||||
#include <px4_vehicle_global_velocity_setpoint.h>
|
||||
#include <px4_vehicle_local_position.h>
|
||||
#include <px4_position_setpoint_triplet.h>
|
||||
#include <px4_offboard_control_mode.h>
|
||||
@ -88,7 +87,6 @@
|
||||
#include <platforms/nuttx/px4_messages/px4_parameter_update.h>
|
||||
#include <platforms/nuttx/px4_messages/px4_vehicle_status.h>
|
||||
#include <platforms/nuttx/px4_messages/px4_vehicle_local_position_setpoint.h>
|
||||
#include <platforms/nuttx/px4_messages/px4_vehicle_global_velocity_setpoint.h>
|
||||
#include <platforms/nuttx/px4_messages/px4_vehicle_local_position.h>
|
||||
#include <platforms/nuttx/px4_messages/px4_position_setpoint_triplet.h>
|
||||
#include <platforms/nuttx/px4_messages/px4_offboard_control_mode.h>
|
||||
@ -119,7 +117,6 @@
|
||||
#include <platforms/posix/px4_messages/px4_parameter_update.h>
|
||||
#include <platforms/posix/px4_messages/px4_vehicle_status.h>
|
||||
#include <platforms/posix/px4_messages/px4_vehicle_local_position_setpoint.h>
|
||||
#include <platforms/posix/px4_messages/px4_vehicle_global_velocity_setpoint.h>
|
||||
#include <platforms/posix/px4_messages/px4_vehicle_local_position.h>
|
||||
#include <platforms/posix/px4_messages/px4_position_setpoint_triplet.h>
|
||||
#endif
|
||||
@ -146,7 +143,6 @@
|
||||
#include <platforms/qurt/px4_messages/px4_parameter_update.h>
|
||||
#include <platforms/qurt/px4_messages/px4_vehicle_status.h>
|
||||
#include <platforms/qurt/px4_messages/px4_vehicle_local_position_setpoint.h>
|
||||
#include <platforms/qurt/px4_messages/px4_vehicle_global_velocity_setpoint.h>
|
||||
#include <platforms/qurt/px4_messages/px4_vehicle_local_position.h>
|
||||
#include <platforms/qurt/px4_messages/px4_position_setpoint_triplet.h>
|
||||
#endif
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user