Skip to content

Commit

Permalink
uORB::Publication simplify and cleanup
Browse files Browse the repository at this point in the history
 - drop linked list
 - base class is now template
 - virtualization no longer required
  • Loading branch information
dagar committed Jun 10, 2019
1 parent bef7a9b commit e2cfe31
Show file tree
Hide file tree
Showing 26 changed files with 128 additions and 420 deletions.
3 changes: 1 addition & 2 deletions src/drivers/md25/md25.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -583,8 +583,7 @@ int md25Sine(const char *deviceName, uint8_t bus, uint8_t address, float amplitu
float prev_revolution = md25.getRevolutions1();

// debug publication
uORB::Publication<debug_key_value_s> debug_msg(NULL,
ORB_ID(debug_key_value));
uORB::PublicationData<debug_key_value_s> debug_msg{ORB_ID(debug_key_value)};

// sine wave for motor 1
md25.resetEncoders();
Expand Down
4 changes: 2 additions & 2 deletions src/examples/segway/BlockSegwayController.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,6 +61,6 @@ void BlockSegwayController::update()
actuators.control[CH_RIGHT] = -_manual.get().x;
}

// update all publications
updatePublications();
// publish
_actuators.update();
}
2 changes: 1 addition & 1 deletion src/examples/segway/blocks.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ BlockUorbEnabledAutopilot::BlockUorbEnabledAutopilot(SuperBlock *parent, const c
_status(ORB_ID(vehicle_status), 20, 0, &getSubscriptions()),

// publications
_actuators(ORB_ID(actuator_controls_0), -1, &getPublications())
_actuators(ORB_ID(actuator_controls_0))
{
}

Expand Down
3 changes: 2 additions & 1 deletion src/examples/segway/blocks.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,8 @@ class __EXPORT BlockUorbEnabledAutopilot : public SuperBlock
uORB::SubscriptionPollable<vehicle_status_s> _status;

// publications
uORB::Publication<actuator_controls_s> _actuators;
uORB::PublicationData<actuator_controls_s> _actuators{ORB_ID(actuator_controls_0)};

public:
BlockUorbEnabledAutopilot(SuperBlock *parent, const char *name);
virtual ~BlockUorbEnabledAutopilot() = default;
Expand Down
38 changes: 0 additions & 38 deletions src/lib/controllib/block/Block.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,6 @@
#include <cstring>

#include <uORB/SubscriptionPollable.hpp>
#include <uORB/Publication.hpp>

namespace control
{
Expand Down Expand Up @@ -118,24 +117,6 @@ void Block::updateSubscriptions()
}
}

void Block::updatePublications()
{
uORB::PublicationNode *pub = getPublications().getHead();
int count = 0;

while (pub != nullptr) {
if (count++ > maxPublicationsPerBlock) {
char name[blockNameLengthMax];
getName(name, blockNameLengthMax);
PX4_ERR("exceeded max publications for block: %s", name);
break;
}

pub->update();
pub = pub->getSibling();
}
}

void SuperBlock::setDt(float dt)
{
Block::setDt(dt);
Expand Down Expand Up @@ -191,26 +172,7 @@ void SuperBlock::updateChildSubscriptions()
}
}

void SuperBlock::updateChildPublications()
{
Block *child = getChildren().getHead();
int count = 0;

while (child != nullptr) {
if (count++ > maxChildrenPerBlock) {
char name[blockNameLengthMax];
getName(name, blockNameLengthMax);
PX4_ERR("exceeded max children for block: %s", name);
break;
}

child->updatePublications();
child = child->getSibling();
}
}

} // namespace control

template class List<uORB::SubscriptionPollableNode *>;
template class List<uORB::PublicationNode *>;
template class List<control::BlockParamBase *>;
12 changes: 0 additions & 12 deletions src/lib/controllib/block/Block.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,6 @@
#pragma once

#include <containers/List.hpp>
#include <uORB/Publication.hpp>
#include <uORB/SubscriptionPollable.hpp>
#include <controllib/block/BlockParam.hpp>

Expand All @@ -50,7 +49,6 @@ namespace control
static constexpr uint8_t maxChildrenPerBlock = 100;
static constexpr uint8_t maxParamsPerBlock = 110;
static constexpr uint8_t maxSubscriptionsPerBlock = 100;
static constexpr uint8_t maxPublicationsPerBlock = 100;
static constexpr uint8_t blockNameLengthMax = 40;

// forward declaration
Expand All @@ -77,7 +75,6 @@ class __EXPORT Block : public ListNode<Block *>

virtual void updateParams();
virtual void updateSubscriptions();
virtual void updatePublications();

virtual void setDt(float dt) { _dt = dt; }
float getDt() { return _dt; }
Expand All @@ -88,15 +85,13 @@ class __EXPORT Block : public ListNode<Block *>

SuperBlock *getParent() { return _parent; }
List<uORB::SubscriptionPollableNode *> &getSubscriptions() { return _subscriptions; }
List<uORB::PublicationNode *> &getPublications() { return _publications; }
List<BlockParamBase *> &getParams() { return _params; }

const char *_name;
SuperBlock *_parent;
float _dt{0.0f};

List<uORB::SubscriptionPollableNode *> _subscriptions;
List<uORB::PublicationNode *> _publications;
List<BlockParamBase *> _params;
};

Expand Down Expand Up @@ -130,18 +125,11 @@ class __EXPORT SuperBlock :

if (getChildren().getHead() != nullptr) { updateChildSubscriptions(); }
}
void updatePublications() override
{
Block::updatePublications();

if (getChildren().getHead() != nullptr) { updateChildPublications(); }
}

protected:
List<Block *> &getChildren() { return _children; }
void updateChildParams();
void updateChildSubscriptions();
void updateChildPublications();

List<Block *> _children;
};
Expand Down
2 changes: 1 addition & 1 deletion src/lib/drivers/accelerometer/PX4Accelerometer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class PX4Accelerometer : public cdev::CDev, public ModuleParams

void configure_filter(float cutoff_freq) { _filter.set_cutoff_frequency(_sample_rate, cutoff_freq); }

uORB::Publication<sensor_accel_s> _sensor_accel_pub;
uORB::PublicationData<sensor_accel_s> _sensor_accel_pub;

math::LowPassFilter2pVector3f _filter{1000, 100};
Integrator _integrator{4000, false};
Expand Down
2 changes: 1 addition & 1 deletion src/lib/drivers/barometer/PX4Barometer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ class PX4Barometer : public cdev::CDev

private:

uORB::Publication<sensor_baro_s> _sensor_baro_pub;
uORB::PublicationData<sensor_baro_s> _sensor_baro_pub;

int _class_device_instance{-1};

Expand Down
2 changes: 1 addition & 1 deletion src/lib/drivers/gyroscope/PX4Gyroscope.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class PX4Gyroscope : public cdev::CDev, public ModuleParams

void configure_filter(float cutoff_freq) { _filter.set_cutoff_frequency(_sample_rate, cutoff_freq); }

uORB::Publication<sensor_gyro_s> _sensor_gyro_pub;
uORB::PublicationData<sensor_gyro_s> _sensor_gyro_pub;

math::LowPassFilter2pVector3f _filter{1000, 100};
Integrator _integrator{4000, true};
Expand Down
2 changes: 1 addition & 1 deletion src/lib/drivers/magnetometer/PX4Magnetometer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ class PX4Magnetometer : public cdev::CDev

private:

uORB::Publication<sensor_mag_s> _sensor_mag_pub;
uORB::PublicationData<sensor_mag_s> _sensor_mag_pub;

const enum Rotation _rotation;

Expand Down
2 changes: 1 addition & 1 deletion src/modules/commander/Commander.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,7 +245,7 @@ class Commander : public ModuleBase<Commander>, public ModuleParams
uORB::SubscriptionData<vehicle_local_position_s> _local_position_sub{ORB_ID(vehicle_local_position)};

// Publications
uORB::Publication<home_position_s> _home_pub{ORB_ID(home_position)};
uORB::PublicationData<home_position_s> _home_pub{ORB_ID(home_position)};

orb_advert_t _status_pub{nullptr};
};
Expand Down
80 changes: 23 additions & 57 deletions src/modules/ekf2/ekf2_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,18 +275,17 @@ class Ekf2 final : public ModuleBase<Ekf2>, public ModuleParams
uORB::Subscription _gps_subs[GPS_MAX_RECEIVERS] {{ORB_ID(vehicle_gps_position), 0}, {ORB_ID(vehicle_gps_position), 1}};
int _gps_orb_instance{ -1};

orb_advert_t _att_pub{nullptr};
orb_advert_t _wind_pub{nullptr};
orb_advert_t _estimator_status_pub{nullptr};
orb_advert_t _ekf_gps_drift_pub{nullptr};
orb_advert_t _estimator_innovations_pub{nullptr};
orb_advert_t _ekf2_timestamps_pub{nullptr};
orb_advert_t _sensor_bias_pub{nullptr};
orb_advert_t _blended_gps_pub{nullptr};

uORB::Publication<vehicle_local_position_s> _vehicle_local_position_pub;
uORB::Publication<vehicle_global_position_s> _vehicle_global_position_pub;
uORB::Publication<vehicle_odometry_s> _vehicle_odometry_pub;
uORB::Publication<ekf2_innovations_s> _estimator_innovations_pub{ORB_ID(ekf2_innovations)};
uORB::Publication<ekf2_timestamps_s> _ekf2_timestamps_pub{ORB_ID(ekf2_timestamps)};
uORB::Publication<ekf_gps_drift_s> _ekf_gps_drift_pub{ORB_ID(ekf_gps_drift)};
uORB::Publication<ekf_gps_position_s> _blended_gps_pub{ORB_ID(ekf_gps_position)};
uORB::Publication<estimator_status_s> _estimator_status_pub{ORB_ID(estimator_status)};
uORB::Publication<sensor_bias_s> _sensor_bias_pub{ORB_ID(sensor_bias)};
uORB::Publication<vehicle_attitude_s> _att_pub{ORB_ID(vehicle_attitude)};
uORB::Publication<vehicle_odometry_s> _vehicle_odometry_pub{ORB_ID(vehicle_odometry)};
uORB::Publication<wind_estimate_s> _wind_pub{ORB_ID(wind_estimate)};
uORB::PublicationData<vehicle_global_position_s> _vehicle_global_position_pub{ORB_ID(vehicle_global_position)};
uORB::PublicationData<vehicle_local_position_s> _vehicle_local_position_pub{ORB_ID(vehicle_local_position)};

Ekf _ekf;

Expand Down Expand Up @@ -535,9 +534,6 @@ Ekf2::Ekf2():
ModuleParams(nullptr),
_perf_update_data(perf_alloc_once(PC_ELAPSED, "EKF2 data acquisition")),
_perf_ekf_update(perf_alloc_once(PC_ELAPSED, "EKF2 update")),
_vehicle_local_position_pub(ORB_ID(vehicle_local_position)),
_vehicle_global_position_pub(ORB_ID(vehicle_global_position)),
_vehicle_odometry_pub(ORB_ID(vehicle_odometry)),
_params(_ekf.getParamHandle()),
_param_ekf2_min_obs_dt(_params->sensor_interval_min_ms),
_param_ekf2_mag_delay(_params->mag_delay_ms),
Expand Down Expand Up @@ -1066,7 +1062,7 @@ void Ekf2::run()
gps.selected = _gps_select_index;

// Publish to the EKF blended GPS topic
orb_publish_auto(ORB_ID(ekf_gps_position), &_blended_gps_pub, &gps, &_gps_orb_instance, ORB_PRIO_LOW);
_blended_gps_pub.publish(gps);

// clear flag to avoid re-use of the same data
_gps_new_output_data = false;
Expand Down Expand Up @@ -1258,7 +1254,7 @@ void Ekf2::run()
vehicle_local_position_s &lpos = _vehicle_local_position_pub.get();

// generate vehicle odometry data
vehicle_odometry_s &odom = _vehicle_odometry_pub.get();
vehicle_odometry_s odom{};

lpos.timestamp = now;
odom.timestamp = lpos.timestamp;
Expand Down Expand Up @@ -1438,7 +1434,7 @@ void Ekf2::run()
_vehicle_local_position_pub.update();

// publish vehicle odometry data
_vehicle_odometry_pub.update();
_vehicle_odometry_pub.publish(odom);

if (_ekf.global_position_is_valid() && !_preflt_fail) {
// generate and publish global position data
Expand Down Expand Up @@ -1509,12 +1505,7 @@ void Ekf2::run()
bias.accel_y = sensors.accelerometer_m_s2[1] - accel_bias[1];
bias.accel_z = sensors.accelerometer_m_s2[2] - accel_bias[2];

if (_sensor_bias_pub == nullptr) {
_sensor_bias_pub = orb_advertise(ORB_ID(sensor_bias), &bias);

} else {
orb_publish(ORB_ID(sensor_bias), _sensor_bias_pub, &bias);
}
_sensor_bias_pub.publish(bias);
}

// publish estimator status
Expand Down Expand Up @@ -1543,12 +1534,7 @@ void Ekf2::run()
status.timeout_flags = 0.0f; // unused
status.pre_flt_fail = _preflt_fail;

if (_estimator_status_pub == nullptr) {
_estimator_status_pub = orb_advertise(ORB_ID(estimator_status), &status);

} else {
orb_publish(ORB_ID(estimator_status), _estimator_status_pub, &status);
}
_estimator_status_pub.publish(status);

// publish GPS drift data only when updated to minimise overhead
float gps_drift[3];
Expand All @@ -1562,12 +1548,7 @@ void Ekf2::run()
drift_data.hspd = gps_drift[2];
drift_data.blocked = blocked;

if (_ekf_gps_drift_pub == nullptr) {
_ekf_gps_drift_pub = orb_advertise(ORB_ID(ekf_gps_drift), &drift_data);

} else {
orb_publish(ORB_ID(ekf_gps_drift), _ekf_gps_drift_pub, &drift_data);
}
_ekf_gps_drift_pub.publish(drift_data);
}

{
Expand Down Expand Up @@ -1732,23 +1713,12 @@ void Ekf2::run()
_preflt_fail = false;
}

if (_estimator_innovations_pub == nullptr) {
_estimator_innovations_pub = orb_advertise(ORB_ID(ekf2_innovations), &innovations);

} else {
orb_publish(ORB_ID(ekf2_innovations), _estimator_innovations_pub, &innovations);
}
_estimator_innovations_pub.publish(innovations);
}

}

// publish ekf2_timestamps
if (_ekf2_timestamps_pub == nullptr) {
_ekf2_timestamps_pub = orb_advertise(ORB_ID(ekf2_timestamps), &ekf2_timestamps);

} else {
orb_publish(ORB_ID(ekf2_timestamps), _ekf2_timestamps_pub, &ekf2_timestamps);
}
_ekf2_timestamps_pub.publish(ekf2_timestamps);
}
}

Expand Down Expand Up @@ -1788,18 +1758,15 @@ bool Ekf2::publish_attitude(const sensor_combined_s &sensors, const hrt_abstime
att.pitchspeed = sensors.gyro_rad[1] - gyro_bias[1];
att.yawspeed = sensors.gyro_rad[2] - gyro_bias[2];

int instance;
orb_publish_auto(ORB_ID(vehicle_attitude), &_att_pub, &att, &instance, ORB_PRIO_HIGH);
_att_pub.publish(att);

return true;

} else if (_replay_mode) {
// in replay mode we have to tell the replay module not to wait for an update
// we do this by publishing an attitude with zero timestamp
vehicle_attitude_s att = {};

int instance;
orb_publish_auto(ORB_ID(vehicle_attitude), &_att_pub, &att, &instance, ORB_PRIO_HIGH);
vehicle_attitude_s att{};
_att_pub.publish(att);
}

return false;
Expand All @@ -1822,8 +1789,7 @@ bool Ekf2::publish_wind_estimate(const hrt_abstime &timestamp)
wind_estimate.variance_north = wind_var[0];
wind_estimate.variance_east = wind_var[1];

int instance;
orb_publish_auto(ORB_ID(wind_estimate), &_wind_pub, &wind_estimate, &instance, ORB_PRIO_DEFAULT);
_wind_pub.publish(wind_estimate);

return true;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,14 +47,6 @@ BlockLocalPositionEstimator::BlockLocalPositionEstimator() :
_sub_sonar(nullptr),
_sub_landing_target_pose(ORB_ID(landing_target_pose), 1000 / 40, 0, &getSubscriptions()),
_sub_airdata(ORB_ID(vehicle_air_data), 0, 0, &getSubscriptions()),

// publications
_pub_lpos(ORB_ID(vehicle_local_position), -1, &getPublications()),
_pub_gpos(ORB_ID(vehicle_global_position), -1, &getPublications()),
_pub_odom(ORB_ID(vehicle_odometry), -1, &getPublications()),
_pub_est_status(ORB_ID(estimator_status), -1, &getPublications()),
_pub_innov(ORB_ID(ekf2_innovations), -1, &getPublications()),

// map projection
_map_ref(),

Expand Down
Loading

0 comments on commit e2cfe31

Please sign in to comment.