mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-21 05:47:35 +08:00
Support topic groups in sdlog2
This commit is contained in:
@@ -1096,7 +1096,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
subs.att_sub = orb_subscribe(ORB_ID(vehicle_attitude));
|
||||
subs.att_sp_sub = orb_subscribe(ORB_ID(vehicle_attitude_setpoint));
|
||||
subs.rates_sp_sub = orb_subscribe(ORB_ID(vehicle_rates_setpoint));
|
||||
subs.act_outputs_sub = orb_subscribe(ORB_ID_VEHICLE_CONTROLS);
|
||||
subs.act_outputs_sub = orb_subscribe(ORB_ID(actuator_outputs));
|
||||
subs.act_controls_sub = orb_subscribe(ORB_ID_VEHICLE_ATTITUDE_CONTROLS);
|
||||
subs.act_controls_1_sub = orb_subscribe(ORB_ID(actuator_controls_1));
|
||||
subs.local_pos_sub = orb_subscribe(ORB_ID(vehicle_local_position));
|
||||
@@ -1473,7 +1473,7 @@ int sdlog2_thread_main(int argc, char *argv[])
|
||||
}
|
||||
|
||||
/* --- ACTUATOR OUTPUTS --- */
|
||||
if (copy_if_updated(ORB_ID(actuator_outputs_0), subs.act_outputs_sub, &buf.act_outputs)) {
|
||||
if (copy_if_updated(ORB_ID(actuator_outputs), subs.act_outputs_sub, &buf.act_outputs)) {
|
||||
log_msg.msg_type = LOG_OUT0_MSG;
|
||||
memcpy(log_msg.body.log_OUT0.output, buf.act_outputs.output, sizeof(log_msg.body.log_OUT0.output));
|
||||
LOGBUFFER_WRITE_AND_COUNT(OUT0);
|
||||
|
||||
Reference in New Issue
Block a user