mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
encoders.msg: remove this topic, it's never published (#5074)
This commit is contained in:
parent
b48c081e5c
commit
ee58f0d11d
@ -49,7 +49,6 @@ set(msg_file_names
|
||||
distance_sensor.msg
|
||||
ekf2_innovations.msg
|
||||
ekf2_replay.msg
|
||||
encoders.msg
|
||||
esc_report.msg
|
||||
esc_status.msg
|
||||
estimator_status.msg
|
||||
|
||||
@ -1,4 +0,0 @@
|
||||
uint8 NUM_ENCODERS = 4
|
||||
|
||||
int64[4] counts # counts of encoder
|
||||
float32[4] velocity # counts of encoder/ second
|
||||
@ -102,7 +102,6 @@
|
||||
#include <uORB/topics/system_power.h>
|
||||
#include <uORB/topics/servorail_status.h>
|
||||
#include <uORB/topics/wind_estimate.h>
|
||||
#include <uORB/topics/encoders.h>
|
||||
#include <uORB/topics/vtol_vehicle_status.h>
|
||||
#include <uORB/topics/time_offset.h>
|
||||
#include <uORB/topics/mc_att_ctrl_status.h>
|
||||
@ -1196,7 +1195,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
struct servorail_status_s servorail_status;
|
||||
struct satellite_info_s sat_info;
|
||||
struct wind_estimate_s wind_estimate;
|
||||
struct encoders_s encoders;
|
||||
struct vtol_vehicle_status_s vtol_status;
|
||||
struct time_offset_s time_offset;
|
||||
struct mc_att_ctrl_status_s mc_att_ctrl_status;
|
||||
@ -1308,7 +1306,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
int system_power_sub;
|
||||
int servorail_status_sub;
|
||||
int wind_sub;
|
||||
int encoders_sub;
|
||||
int tsync_sub;
|
||||
int mc_att_ctrl_status_sub;
|
||||
int ctrl_state_sub;
|
||||
@ -1354,7 +1351,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
subs.tsync_sub = -1;
|
||||
subs.mc_att_ctrl_status_sub = -1;
|
||||
subs.ctrl_state_sub = -1;
|
||||
subs.encoders_sub = -1;
|
||||
subs.innov_sub = -1;
|
||||
subs.cam_trig_sub = -1;
|
||||
subs.replay_sub = -1;
|
||||
@ -2215,16 +2211,6 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
LOGBUFFER_WRITE_AND_COUNT(WIND);
|
||||
}
|
||||
|
||||
/* --- ENCODERS --- */
|
||||
if (copy_if_updated(ORB_ID(encoders), &subs.encoders_sub, &buf.encoders)) {
|
||||
log_msg.msg_type = LOG_ENCD_MSG;
|
||||
log_msg.body.log_ENCD.cnt0 = buf.encoders.counts[0];
|
||||
log_msg.body.log_ENCD.vel0 = buf.encoders.velocity[0];
|
||||
log_msg.body.log_ENCD.cnt1 = buf.encoders.counts[1];
|
||||
log_msg.body.log_ENCD.vel1 = buf.encoders.velocity[1];
|
||||
LOGBUFFER_WRITE_AND_COUNT(ENCD);
|
||||
}
|
||||
|
||||
/* --- TIMESYNC OFFSET --- */
|
||||
if (copy_if_updated(ORB_ID(time_offset), &subs.tsync_sub, &buf.time_offset)) {
|
||||
log_msg.msg_type = LOG_TSYN_MSG;
|
||||
|
||||
@ -47,7 +47,6 @@
|
||||
#include "topics/vehicle_rates_setpoint.h"
|
||||
#include "topics/actuator_outputs.h"
|
||||
#include "topics/actuator_direct.h"
|
||||
#include "topics/encoders.h"
|
||||
#include "topics/tecs_status.h"
|
||||
#include "topics/rc_channels.h"
|
||||
#include "topics/filtered_bottom_flow.h"
|
||||
@ -118,7 +117,6 @@ template class __EXPORT Publication<vehicle_attitude_setpoint_s>;
|
||||
template class __EXPORT Publication<vehicle_rates_setpoint_s>;
|
||||
template class __EXPORT Publication<actuator_outputs_s>;
|
||||
template class __EXPORT Publication<actuator_direct_s>;
|
||||
template class __EXPORT Publication<encoders_s>;
|
||||
template class __EXPORT Publication<tecs_status_s>;
|
||||
template class __EXPORT Publication<rc_channels_s>;
|
||||
template class __EXPORT Publication<filtered_bottom_flow_s>;
|
||||
|
||||
@ -45,7 +45,6 @@
|
||||
#include "topics/hil_sensor.h"
|
||||
#include "topics/vehicle_attitude.h"
|
||||
#include "topics/vehicle_global_position.h"
|
||||
#include "topics/encoders.h"
|
||||
#include "topics/position_setpoint_triplet.h"
|
||||
#include "topics/vehicle_status.h"
|
||||
#include "topics/manual_control_setpoint.h"
|
||||
@ -162,7 +161,6 @@ template class __EXPORT Subscription<sensor_combined_s>;
|
||||
template class __EXPORT Subscription<hil_sensor_s>;
|
||||
template class __EXPORT Subscription<vehicle_attitude_s>;
|
||||
template class __EXPORT Subscription<vehicle_global_position_s>;
|
||||
template class __EXPORT Subscription<encoders_s>;
|
||||
template class __EXPORT Subscription<position_setpoint_triplet_s>;
|
||||
template class __EXPORT Subscription<vehicle_status_s>;
|
||||
template class __EXPORT Subscription<manual_control_setpoint_s>;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user