PX4 Firmware
PX4 Autopilot Software http://px4.io
uORB::Publication< T > Class Template Reference

Base publication wrapper class. More...

#include <Publication.hpp>

Inheritance diagram for uORB::Publication< T >:
Collaboration diagram for uORB::Publication< T >:

Public Member Functions

 Publication (const orb_metadata *meta)
 Constructor. More...
 
 ~Publication ()
 
bool publish (const T &data)
 Publish the struct. More...
 

Protected Attributes

const orb_metadata_meta
 
orb_advert_t _handle {nullptr}
 

Detailed Description

template<typename T>
class uORB::Publication< T >

Base publication wrapper class.

Definition at line 52 of file Publication.hpp.

Constructor & Destructor Documentation

◆ Publication()

template<typename T>
uORB::Publication< T >::Publication ( const orb_metadata meta)
inline

Constructor.

Parameters
metaThe uORB metadata (usually from the ORB_ID() macro) for the topic.

Definition at line 61 of file Publication.hpp.

◆ ~Publication()

template<typename T>
uORB::Publication< T >::~Publication ( )
inline

Definition at line 62 of file Publication.hpp.

Member Function Documentation

◆ publish()

template<typename T>
bool uORB::Publication< T >::publish ( const T &  data)
inline

Publish the struct.

Parameters
dataThe uORB message struct we are updating.

Definition at line 68 of file Publication.hpp.

Referenced by CollisionPrevention::_updateObstacleMap(), UavcanServers::cb_getset(), ObstacleAvoidance::checkAvoidanceProgress(), Sensors::diff_pres_poll(), Commander::handle_command_motor_test(), MavlinkParametersManager::handle_message(), MavlinkReceiver::handle_message_att_pos_mocap(), MavlinkReceiver::handle_message_battery_status(), MavlinkReceiver::handle_message_cellular_status(), MavlinkReceiver::handle_message_collision(), MavlinkReceiver::handle_message_debug(), MavlinkReceiver::handle_message_debug_float_array(), MavlinkReceiver::handle_message_debug_vect(), MavlinkReceiver::handle_message_follow_target(), MavlinkReceiver::handle_message_hil_gps(), MavlinkReceiver::handle_message_hil_optical_flow(), MavlinkReceiver::handle_message_hil_sensor(), MavlinkReceiver::handle_message_hil_state_quaternion(), MavlinkReceiver::handle_message_landing_target(), MavlinkReceiver::handle_message_named_value_float(), MavlinkReceiver::handle_message_obstacle_distance(), MavlinkReceiver::handle_message_odometry(), MavlinkReceiver::handle_message_onboard_computer_status(), MavlinkReceiver::handle_message_optical_flow_rad(), MavlinkReceiver::handle_message_set_actuator_control_target(), MavlinkReceiver::handle_message_set_attitude_target(), MavlinkReceiver::handle_message_set_position_target_global_int(), MavlinkReceiver::handle_message_set_position_target_local_ned(), MavlinkReceiver::handle_message_statustext(), MavlinkReceiver::handle_message_trajectory_representation_waypoints(), MavlinkReceiver::handle_message_vision_position_estimate(), PX4IO::io_handle_status(), PX4IO::io_handle_vservo(), MissionBlock::issue_command(), FixedwingPositionControl::landing_status_publish(), CollisionPrevention::modifySetpoint(), GpsFailure::on_active(), MavlinkULog::publish_ack(), Ekf2::publish_attitude(), IridiumSBD::publish_iridium_status(), Navigator::publish_mission_result(), Navigator::publish_position_setpoint_triplet(), MulticopterAttitudeControl::publish_rates_setpoint(), CameraCapture::publish_trigger(), MulticopterRateControl::Run(), AttitudeEstimatorQ::Run(), Commander::run(), FixedwingAttitudeControl::Run(), MulticopterPositionControl::Run(), RoverPositionControl::run(), VtolAttitudeControl::Run(), Sensors::run(), Ekf2::Run(), Navigator::run(), land_detector::LandDetector::Run(), AirspeedModule::select_airspeed_and_publish(), FlightTaskOrbit::sendTelemetry(), sensors::VotedSensorsUpdate::sensorsPoll(), FixedwingPositionControl::status_publish(), FixedwingPositionControl::tecs_status_publish(), landing_target_estimator::LandingTargetEstimator::update(), uORB::PublicationData< vehicle_global_position_s >::update(), MavlinkMissionManager::update_active_mission(), ADC::update_adc_report(), Commander::update_control_mode(), ADC::update_system_power(), ObstacleAvoidance::updateAvoidanceDesiredSetpoints(), and FixedwingAttitudeControl::vehicle_manual_poll().

Member Data Documentation

◆ _handle

template<typename T>
orb_advert_t uORB::Publication< T >::_handle {nullptr}
protected

◆ _meta

template<typename T>
const orb_metadata* uORB::Publication< T >::_meta
protected

The documentation for this class was generated from the following file: