mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
Replace PublicationQueued with Publication to automatically configure ORB_QUEUE_LENGTH
This commit is contained in:
parent
90c366f369
commit
eac9a6b68b
@ -101,7 +101,7 @@ public:
|
||||
private:
|
||||
|
||||
// Publishers
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<camera_trigger_s> _trigger_pub{ORB_ID(camera_trigger)};
|
||||
|
||||
// Subscribers
|
||||
|
||||
@ -179,7 +179,7 @@ private:
|
||||
|
||||
orb_advert_t _trigger_pub;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> _cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> _cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
param_t _p_mode;
|
||||
param_t _p_activation_time;
|
||||
@ -504,7 +504,7 @@ CameraTrigger::test()
|
||||
vcmd.param5 = 1.0;
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_DIGICAM_CONTROL;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
vcmd_pub.publish(vcmd);
|
||||
}
|
||||
|
||||
|
||||
@ -176,7 +176,7 @@ private:
|
||||
const Instance _instance;
|
||||
|
||||
uORB::Subscription _orb_inject_data_sub{ORB_ID(gps_inject_data)};
|
||||
uORB::PublicationQueued<gps_dump_s> _dump_communication_pub{ORB_ID(gps_dump)};
|
||||
uORB::Publication<gps_dump_s> _dump_communication_pub{ORB_ID(gps_dump)};
|
||||
gps_dump_s *_dump_to_device{nullptr};
|
||||
gps_dump_s *_dump_from_device{nullptr};
|
||||
bool _should_dump_communication{false}; ///< if true, dump communication
|
||||
|
||||
@ -162,7 +162,7 @@ private:
|
||||
char _device[20];
|
||||
orb_advert_t _t_outputs;
|
||||
orb_advert_t _t_esc_status;
|
||||
uORB::PublicationQueued<tune_control_s> _tune_control_pub{ORB_ID(tune_control)};
|
||||
uORB::Publication<tune_control_s> _tune_control_pub{ORB_ID(tune_control)};
|
||||
unsigned int _num_outputs;
|
||||
bool _primary_pwm_device;
|
||||
bool _motortest;
|
||||
|
||||
@ -713,7 +713,7 @@ PX4IO::init()
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_DO_FLIGHTTERMINATION;
|
||||
|
||||
/* send command once */
|
||||
uORB::PublicationQueued<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
vcmd_pub.publish(vcmd);
|
||||
|
||||
/* spin here until IO's state has propagated into the system */
|
||||
@ -746,7 +746,7 @@ PX4IO::init()
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_COMPONENT_ARM_DISARM;
|
||||
|
||||
/* send command once */
|
||||
uORB::PublicationQueued<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
vcmd_pub.publish(vcmd);
|
||||
|
||||
/* spin here until IO's state has propagated into the system */
|
||||
|
||||
@ -648,7 +648,7 @@ int RCInput::custom_command(int argc, char *argv[])
|
||||
const char *verb = argv[0];
|
||||
|
||||
if (!strcmp(verb, "bind")) {
|
||||
uORB::PublicationQueued<vehicle_command_s> vehicle_command_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> vehicle_command_pub{ORB_ID(vehicle_command)};
|
||||
vehicle_command_s vcmd{};
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_START_RX_PAIR;
|
||||
vcmd.timestamp = hrt_absolute_time();
|
||||
|
||||
@ -79,8 +79,8 @@ private:
|
||||
|
||||
uORB::Subscription _armed_sub{ORB_ID(actuator_armed)};
|
||||
uORB::Publication<safety_s> _to_safety{ORB_ID(safety)};
|
||||
uORB::PublicationQueued<vehicle_command_s> _to_command{ORB_ID(vehicle_command)};
|
||||
uORB::PublicationQueued<led_control_s> _to_led_control{ORB_ID(led_control)};
|
||||
uORB::Publication<vehicle_command_s> _to_command{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<led_control_s> _to_led_control{ORB_ID(led_control)};
|
||||
uORB::Publication<tune_control_s> _to_tune_control{ORB_ID(tune_control)};
|
||||
|
||||
safety_s _safety{};
|
||||
|
||||
@ -166,7 +166,7 @@ void ToneAlarm::Run()
|
||||
} else if (_play_tone && !tune_control.tune_override) {
|
||||
// otherwise re-publish tune to process next
|
||||
PX4_DEBUG("tune already playing, requeing tune: %d", tune_control.tune_id);
|
||||
uORB::PublicationQueued<tune_control_s> tune_control_pub{ORB_ID(tune_control)};
|
||||
uORB::Publication<tune_control_s> tune_control_pub{ORB_ID(tune_control)};
|
||||
tune_control.timestamp = hrt_absolute_time();
|
||||
tune_control_pub.publish(tune_control);
|
||||
}
|
||||
|
||||
@ -163,7 +163,7 @@ private:
|
||||
|
||||
// uORB topic handle for MAVLink parameter responses
|
||||
uORB::Publication<uavcan_parameter_value_s> _param_response_pub{ORB_ID(uavcan_parameter_value)};
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
typedef uavcan::MethodBinder<UavcanServers *,
|
||||
void (UavcanServers::*)(const uavcan::ServiceCallResult<uavcan::protocol::param::GetSet> &)> GetSetCallback;
|
||||
|
||||
@ -124,7 +124,7 @@ protected:
|
||||
|
||||
uORB::Publication<vehicle_trajectory_waypoint_s> _pub_traj_wp_avoidance_desired{ORB_ID(vehicle_trajectory_waypoint_desired)}; /**< trajectory waypoint desired publication */
|
||||
uORB::Publication<position_controller_status_s> _pub_pos_control_status{ORB_ID(position_controller_status)}; /**< position controller status publication */
|
||||
uORB::PublicationQueued<vehicle_command_s> _pub_vehicle_command{ORB_ID(vehicle_command)}; /**< vehicle command do publication */
|
||||
uORB::Publication<vehicle_command_s> _pub_vehicle_command{ORB_ID(vehicle_command)}; /**< vehicle command do publication */
|
||||
|
||||
matrix::Vector3f _curr_wp = {}; /**< current position triplet */
|
||||
matrix::Vector3f _position = {}; /**< current vehicle position */
|
||||
|
||||
@ -129,7 +129,7 @@ private:
|
||||
|
||||
uORB::Publication<collision_constraints_s> _constraints_pub{ORB_ID(collision_constraints)}; /**< constraints publication */
|
||||
uORB::Publication<obstacle_distance_s> _obstacle_distance_pub{ORB_ID(obstacle_distance_fused)}; /**< obstacle_distance publication */
|
||||
uORB::PublicationQueued<vehicle_command_s> _vehicle_command_pub{ORB_ID(vehicle_command)}; /**< vehicle command do publication */
|
||||
uORB::Publication<vehicle_command_s> _vehicle_command_pub{ORB_ID(vehicle_command)}; /**< vehicle command do publication */
|
||||
|
||||
uORB::SubscriptionData<obstacle_distance_s> _sub_obstacle_distance{ORB_ID(obstacle_distance)}; /**< obstacle distances received form a range sensor */
|
||||
uORB::SubscriptionData<vehicle_attitude_s> _sub_vehicle_attitude{ORB_ID(vehicle_attitude)};
|
||||
|
||||
@ -66,7 +66,7 @@ private:
|
||||
void Publish(const hrt_abstime ×tamp_sample, float x, float y, float z, uint8_t clip_count[3]);
|
||||
void UpdateClipLimit();
|
||||
|
||||
uORB::PublicationQueuedMulti<sensor_accel_s> _sensor_pub;
|
||||
uORB::PublicationMulti<sensor_accel_s> _sensor_pub;
|
||||
uORB::PublicationMulti<sensor_accel_fifo_s> _sensor_fifo_pub;
|
||||
|
||||
uint32_t _device_id{0};
|
||||
|
||||
@ -64,7 +64,7 @@ public:
|
||||
private:
|
||||
void Publish(const hrt_abstime ×tamp_sample, float x, float y, float z);
|
||||
|
||||
uORB::PublicationQueuedMulti<sensor_gyro_s> _sensor_pub;
|
||||
uORB::PublicationMulti<sensor_gyro_s> _sensor_pub;
|
||||
uORB::PublicationMulti<sensor_gyro_fifo_s> _sensor_fifo_pub;
|
||||
|
||||
uint32_t _device_id{0};
|
||||
|
||||
@ -61,7 +61,7 @@ public:
|
||||
int get_class_instance() { return _class_device_instance; };
|
||||
|
||||
private:
|
||||
uORB::PublicationQueuedMulti<sensor_mag_s> _sensor_pub;
|
||||
uORB::PublicationMulti<sensor_mag_s> _sensor_pub;
|
||||
|
||||
uint32_t _device_id{0};
|
||||
const enum Rotation _rotation;
|
||||
|
||||
@ -196,7 +196,7 @@ private:
|
||||
|
||||
uORB::Subscription _sub_vehicle_command{ORB_ID(vehicle_command)}; /**< topic handle on which commands are received */
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> _pub_vehicle_command_ack{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> _pub_vehicle_command_ack{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
int _initTask(FlightTaskIndex task_index);
|
||||
};
|
||||
|
||||
@ -72,7 +72,7 @@ _control_latency_perf(perf_alloc(PC_ELAPSED, "control latency"))
|
||||
|
||||
// Enforce the existence of the test_motor topic, so we won't miss initial publications
|
||||
test_motor_s test{};
|
||||
uORB::PublicationQueued<test_motor_s> test_motor_pub{ORB_ID(test_motor)};
|
||||
uORB::Publication<test_motor_s> test_motor_pub{ORB_ID(test_motor)};
|
||||
test_motor_pub.publish(test);
|
||||
_motor_test.test_motor_sub.subscribe();
|
||||
}
|
||||
|
||||
@ -86,7 +86,7 @@ static void arm_auth_request_msg_send()
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_ARM_AUTHORIZATION_REQUEST;
|
||||
vcmd.target_system = arm_parameters.struct_value.authorizer_system_id;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
vcmd_pub.publish(vcmd);
|
||||
}
|
||||
|
||||
|
||||
@ -115,7 +115,7 @@ static struct vehicle_status_flags_s status_flags = {};
|
||||
void *commander_low_prio_loop(void *arg);
|
||||
|
||||
static void answer_command(const vehicle_command_s &cmd, unsigned result,
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> &command_ack_pub);
|
||||
uORB::Publication<vehicle_command_ack_s> &command_ack_pub);
|
||||
|
||||
#if defined(BOARD_HAS_POWER_CONTROL)
|
||||
static orb_advert_t power_button_state_pub = nullptr;
|
||||
@ -184,7 +184,7 @@ static bool send_vehicle_command(uint16_t cmd, float param1 = NAN, float param2
|
||||
|
||||
vcmd.timestamp = hrt_absolute_time();
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
|
||||
return vcmd_pub.publish(vcmd);
|
||||
}
|
||||
@ -532,7 +532,7 @@ Commander::Commander() :
|
||||
|
||||
bool
|
||||
Commander::handle_command(vehicle_status_s *status_local, const vehicle_command_s &cmd, actuator_armed_s *armed_local,
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> &command_ack_pub)
|
||||
uORB::Publication<vehicle_command_ack_s> &command_ack_pub)
|
||||
{
|
||||
/* only handle commands that are meant to be handled by this system and component */
|
||||
if (cmd.target_system != status_local->system_id || ((cmd.target_component != status_local->component_id)
|
||||
@ -3377,7 +3377,7 @@ Commander::print_reject_arm(const char *msg)
|
||||
}
|
||||
|
||||
void answer_command(const vehicle_command_s &cmd, unsigned result,
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> &command_ack_pub)
|
||||
uORB::Publication<vehicle_command_ack_s> &command_ack_pub)
|
||||
{
|
||||
switch (result) {
|
||||
case vehicle_command_s::VEHICLE_CMD_RESULT_ACCEPTED:
|
||||
@ -3425,7 +3425,7 @@ void *commander_low_prio_loop(void *arg)
|
||||
int cmd_sub = orb_subscribe(ORB_ID(vehicle_command));
|
||||
|
||||
/* command ack */
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
/* wakeup source(s) */
|
||||
px4_pollfd_struct_t fds[1];
|
||||
|
||||
@ -140,7 +140,7 @@ private:
|
||||
void estimator_check(const vehicle_status_flags_s &status_flags);
|
||||
|
||||
bool handle_command(vehicle_status_s *status, const vehicle_command_s &cmd, actuator_armed_s *armed,
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> &command_ack_pub);
|
||||
uORB::Publication<vehicle_command_ack_s> &command_ack_pub);
|
||||
|
||||
unsigned handle_command_motor_test(const vehicle_command_s &cmd);
|
||||
|
||||
@ -420,7 +420,7 @@ private:
|
||||
|
||||
uORB::PublicationData<home_position_s> _home_pub{ORB_ID(home_position)};
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
};
|
||||
|
||||
|
||||
@ -614,7 +614,7 @@ bool calibrate_cancel_check(orb_advert_t *mavlink_log_pub, const hrt_abstime &ca
|
||||
command_ack.target_component = cmd.source_component;
|
||||
command_ack.timestamp = hrt_absolute_time();
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
command_ack_pub.publish(command_ack);
|
||||
|
||||
return ret;
|
||||
|
||||
@ -65,7 +65,7 @@ private:
|
||||
/** Publish tune control to interrupt any sound */
|
||||
void stop_tune();
|
||||
|
||||
uORB::PublicationQueued<tune_control_s> _tune_control_pub{ORB_ID(tune_control)};
|
||||
uORB::Publication<tune_control_s> _tune_control_pub{ORB_ID(tune_control)};
|
||||
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
|
||||
|
||||
bool _was_armed = false;
|
||||
|
||||
@ -126,7 +126,7 @@ void SendEvent::answer_command(const vehicle_command_s &cmd, unsigned result)
|
||||
command_ack.target_system = cmd.source_system;
|
||||
command_ack.target_component = cmd.source_component;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
command_ack_pub.publish(command_ack);
|
||||
}
|
||||
|
||||
|
||||
@ -97,7 +97,7 @@ private:
|
||||
int _old_nav_state = -1;
|
||||
int _old_battery_status_warning = -1;
|
||||
|
||||
uORB::PublicationQueued<led_control_s> _led_control_pub{ORB_ID(led_control)};
|
||||
uORB::Publication<led_control_s> _led_control_pub{ORB_ID(led_control)};
|
||||
|
||||
};
|
||||
|
||||
|
||||
@ -87,7 +87,7 @@ private:
|
||||
|
||||
int _stack_task_index{0};
|
||||
|
||||
uORB::PublicationQueued<task_stack_info_s> _task_stack_info_pub{ORB_ID(task_stack_info)};
|
||||
uORB::Publication<task_stack_info_s> _task_stack_info_pub{ORB_ID(task_stack_info)};
|
||||
#endif
|
||||
uORB::Publication<cpuload_s> _cpuload_pub {ORB_ID(cpuload)};
|
||||
|
||||
|
||||
@ -77,7 +77,7 @@ private:
|
||||
int publish_message();
|
||||
|
||||
ulog_stream_s _ulog_stream_data{};
|
||||
uORB::PublicationQueued<ulog_stream_s> _ulog_stream_pub{ORB_ID(ulog_stream)};
|
||||
uORB::Publication<ulog_stream_s> _ulog_stream_pub{ORB_ID(ulog_stream)};
|
||||
int _ulog_stream_ack_sub{-1};
|
||||
bool _need_reliable_transfer{false};
|
||||
bool _is_started{false};
|
||||
|
||||
@ -1971,7 +1971,7 @@ void Logger::ack_vehicle_command(vehicle_command_s *cmd, uint32_t result)
|
||||
vehicle_command_ack.target_system = cmd->source_system;
|
||||
vehicle_command_ack.target_component = cmd->source_component;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
cmd_ack_pub.publish(vehicle_command_ack);
|
||||
}
|
||||
|
||||
|
||||
@ -2149,7 +2149,7 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
uORB::Subscription ack_sub{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
/* command ack */
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
uORB::Subscription mavlink_log_sub{ORB_ID(mavlink_log)};
|
||||
|
||||
|
||||
@ -128,7 +128,7 @@ protected:
|
||||
uORB::Publication<rc_parameter_map_s> _rc_param_map_pub{ORB_ID(rc_parameter_map)};
|
||||
rc_parameter_map_s _rc_param_map{};
|
||||
|
||||
uORB::PublicationQueued<uavcan_parameter_request_s> _uavcan_parameter_request_pub{ORB_ID(uavcan_parameter_request)};
|
||||
uORB::Publication<uavcan_parameter_request_s> _uavcan_parameter_request_pub{ORB_ID(uavcan_parameter_request)};
|
||||
// enforce ORB_ID(uavcan_parameter_request) constants that map to MAVLINK defines
|
||||
static_assert(uavcan_parameter_request_s::MESSAGE_TYPE_PARAM_REQUEST_READ == MAVLINK_MSG_ID_PARAM_REQUEST_READ,
|
||||
"uavcan_parameter_request_s MAVLINK_MSG_ID_PARAM_REQUEST_READ constant mismatch");
|
||||
|
||||
@ -283,10 +283,10 @@ private:
|
||||
uORB::PublicationMulti<radio_status_s> _radio_status_pub{ORB_ID(radio_status)};
|
||||
|
||||
// ORB publications (queue length > 1)
|
||||
uORB::PublicationQueued<gps_inject_data_s> _gps_inject_data_pub{ORB_ID(gps_inject_data)};
|
||||
uORB::PublicationQueued<transponder_report_s> _transponder_report_pub{ORB_ID(transponder_report)};
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> _cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::PublicationQueued<vehicle_command_s> _cmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<gps_inject_data_s> _gps_inject_data_pub{ORB_ID(gps_inject_data)};
|
||||
uORB::Publication<transponder_report_s> _transponder_report_pub{ORB_ID(transponder_report)};
|
||||
uORB::Publication<vehicle_command_ack_s> _cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_s> _cmd_pub{ORB_ID(vehicle_command)};
|
||||
|
||||
// ORB subscriptions
|
||||
uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)};
|
||||
|
||||
@ -51,5 +51,5 @@ private:
|
||||
char _tune_buffer[MAX_TUNE_LEN] {0};
|
||||
hrt_abstime _next_publish_time {0};
|
||||
|
||||
uORB::PublicationQueued<tune_control_s> _tune_control_pub{ORB_ID(tune_control)};
|
||||
uORB::Publication<tune_control_s> _tune_control_pub{ORB_ID(tune_control)};
|
||||
};
|
||||
|
||||
@ -101,7 +101,7 @@ private:
|
||||
Takeoff _takeoff; /**< state machine and ramp to bring the vehicle off the ground without jumps */
|
||||
|
||||
uORB::Publication<vehicle_attitude_setpoint_s> _vehicle_attitude_setpoint_pub;
|
||||
uORB::PublicationQueued<vehicle_command_s> _pub_vehicle_command{ORB_ID(vehicle_command)}; /**< vehicle command publication */
|
||||
uORB::Publication<vehicle_command_s> _pub_vehicle_command{ORB_ID(vehicle_command)}; /**< vehicle command publication */
|
||||
orb_advert_t _mavlink_log_pub{nullptr};
|
||||
|
||||
uORB::Publication<landing_gear_s> _landing_gear_pub{ORB_ID(landing_gear)};
|
||||
|
||||
@ -62,7 +62,7 @@ int MuorbTestExample::DefaultTest()
|
||||
int i = 0;
|
||||
|
||||
uORB::Subscription sub_vc{ORB_ID(vehicle_command)};
|
||||
uORB::PublicationQueued<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<esc_status_s> pub_id{ORB_ID(esc_status)};
|
||||
pub_id.publish(m_esc_status);
|
||||
|
||||
@ -103,7 +103,7 @@ int MuorbTestExample::DefaultTest()
|
||||
int MuorbTestExample::PingPongTest()
|
||||
{
|
||||
int i = 0;
|
||||
uORB::PublicationQueued<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Subscription sub_esc_status{ORB_ID(esc_status)};
|
||||
|
||||
while (!appState.exitRequested()) {
|
||||
|
||||
@ -343,8 +343,8 @@ private:
|
||||
|
||||
orb_advert_t _mavlink_log_pub{nullptr}; /**< the uORB advert to send messages over mavlink */
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> _vehicle_cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::PublicationQueued<vehicle_command_s> _vehicle_cmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_ack_s> _vehicle_cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_s> _vehicle_cmd_pub{ORB_ID(vehicle_command)};
|
||||
|
||||
// Subscriptions
|
||||
home_position_s _home_pos{}; /**< home position for RTL */
|
||||
|
||||
@ -1006,7 +1006,7 @@ void Navigator::fake_traffic(const char *callsign, float distance, float directi
|
||||
|
||||
#endif /* BOARD_HAS_NO_UUID */
|
||||
|
||||
uORB::PublicationQueued<transponder_report_s> tr_pub{ORB_ID(transponder_report)};
|
||||
uORB::Publication<transponder_report_s> tr_pub{ORB_ID(transponder_report)};
|
||||
tr_pub.publish(tr);
|
||||
}
|
||||
|
||||
|
||||
@ -188,7 +188,7 @@ private:
|
||||
uORB::Publication<vehicle_odometry_s> _visual_odometry_pub{ORB_ID(vehicle_visual_odometry)};
|
||||
uORB::Publication<vehicle_odometry_s> _mocap_odometry_pub{ORB_ID(vehicle_mocap_odometry)};
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
uORB::PublicationMulti<distance_sensor_s> *_dist_pubs[RANGE_FINDER_MAX_SENSORS] {};
|
||||
uint8_t _dist_sensor_ids[RANGE_FINDER_MAX_SENSORS] {};
|
||||
|
||||
@ -225,7 +225,7 @@ void TemperatureCompensationModule::Run()
|
||||
command_ack.target_system = cmd.source_system;
|
||||
command_ack.target_component = cmd.source_component;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
command_ack_pub.publish(command_ack);
|
||||
}
|
||||
}
|
||||
@ -344,7 +344,7 @@ int TemperatureCompensationModule::custom_command(int argc, char *argv[])
|
||||
|| calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN);
|
||||
vcmd.command = vehicle_command_s::VEHICLE_CMD_PREFLIGHT_CALIBRATION;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> vcmd_pub{ORB_ID(vehicle_command)};
|
||||
vcmd_pub.publish(vcmd);
|
||||
|
||||
return PX4_OK;
|
||||
|
||||
@ -87,7 +87,7 @@ public:
|
||||
private:
|
||||
void publish_led_control(led_control_s &led_control);
|
||||
|
||||
uORB::PublicationQueued<led_control_s> _led_control_pub{ORB_ID(led_control)};
|
||||
uORB::Publication<led_control_s> _led_control_pub{ORB_ID(led_control)};
|
||||
|
||||
bool _force_task_exit = false;
|
||||
int _control_task = -1; // task handle for task
|
||||
|
||||
@ -163,10 +163,4 @@ private:
|
||||
T _data{};
|
||||
};
|
||||
|
||||
|
||||
template<class T>
|
||||
using PublicationQueued = Publication<T, T::ORB_QUEUE_LENGTH>;
|
||||
|
||||
|
||||
|
||||
} // namespace uORB
|
||||
|
||||
@ -122,8 +122,4 @@ private:
|
||||
T _data{};
|
||||
};
|
||||
|
||||
|
||||
template<class T>
|
||||
using PublicationQueuedMulti = PublicationMulti<T, T::ORB_QUEUE_LENGTH>;
|
||||
|
||||
} // namespace uORB
|
||||
|
||||
@ -369,7 +369,7 @@ void InputMavlinkCmdMount::_ack_vehicle_command(vehicle_command_s *cmd)
|
||||
vehicle_command_ack.target_system = cmd->source_system;
|
||||
vehicle_command_ack.target_component = cmd->source_component;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> cmd_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
cmd_ack_pub.publish(vehicle_command_ack);
|
||||
}
|
||||
|
||||
|
||||
@ -62,7 +62,7 @@ public:
|
||||
|
||||
private:
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_s> _vehicle_command_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> _vehicle_command_pub{ORB_ID(vehicle_command)};
|
||||
};
|
||||
|
||||
|
||||
|
||||
@ -183,7 +183,7 @@ VtolAttitudeControl::handle_command()
|
||||
command_ack.target_system = _vehicle_cmd.source_system;
|
||||
command_ack.target_component = _vehicle_cmd.source_component;
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uORB::Publication<vehicle_command_ack_s> command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
command_ack_pub.publish(command_ack);
|
||||
}
|
||||
}
|
||||
|
||||
@ -124,7 +124,7 @@ int inject_failure(uint8_t unit, uint8_t type, uint8_t instance)
|
||||
|
||||
uORB::Subscription command_ack_sub{ORB_ID(vehicle_command_ack)};
|
||||
|
||||
uORB::PublicationQueued<vehicle_command_s> command_pub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_s> command_pub{ORB_ID(vehicle_command)};
|
||||
vehicle_command_s command{};
|
||||
|
||||
command.command = vehicle_command_s::VEHICLE_CMD_INJECT_FAILURE;
|
||||
|
||||
@ -58,7 +58,7 @@ static void publish_led_control(led_control_s &led_control)
|
||||
{
|
||||
led_control.timestamp = hrt_absolute_time();
|
||||
|
||||
uORB::PublicationQueued<led_control_s> led_control_pub{ORB_ID(led_control)};
|
||||
uORB::Publication<led_control_s> led_control_pub{ORB_ID(led_control)};
|
||||
led_control_pub.publish(led_control);
|
||||
}
|
||||
|
||||
|
||||
@ -61,7 +61,7 @@ void motor_test(unsigned channel, float value, uint8_t driver_instance, int time
|
||||
test_motor.driver_instance = driver_instance;
|
||||
test_motor.timeout_ms = timeout_ms;
|
||||
|
||||
uORB::PublicationQueued<test_motor_s> test_motor_pub{ORB_ID(test_motor)};
|
||||
uORB::Publication<test_motor_s> test_motor_pub{ORB_ID(test_motor)};
|
||||
test_motor_pub.publish(test_motor);
|
||||
|
||||
if (test_motor.action == test_motor_s::ACTION_STOP) {
|
||||
|
||||
@ -60,7 +60,7 @@ static void usage();
|
||||
|
||||
static void publish_tune_control(tune_control_s &tune_control)
|
||||
{
|
||||
uORB::PublicationQueued<tune_control_s> tune_control_pub{ORB_ID(tune_control)};
|
||||
uORB::Publication<tune_control_s> tune_control_pub{ORB_ID(tune_control)};
|
||||
tune_control.timestamp = hrt_absolute_time();
|
||||
tune_control_pub.publish(tune_control);
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user