Skip to content

Commit

Permalink
mavlink: update streams to use orb polling
Browse files Browse the repository at this point in the history
  • Loading branch information
jnippula committed Apr 15, 2024
1 parent 436ee3a commit aa9e6a0
Show file tree
Hide file tree
Showing 74 changed files with 1,029 additions and 70 deletions.
12 changes: 11 additions & 1 deletion src/modules/mavlink/streams/ACTUATOR_OUTPUT_STATUS.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,17 @@ class MavlinkStreamActuatorOutputStatus : public MavlinkStream
}

private:
explicit MavlinkStreamActuatorOutputStatus(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamActuatorOutputStatus(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamActuatorOutputStatus()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] { ORB_ID::actuator_outputs };

uORB::Subscription _act_output_sub{ORB_ID(actuator_outputs)};

Expand Down
12 changes: 11 additions & 1 deletion src/modules/mavlink/streams/ADSB_VEHICLE.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,17 @@ class MavlinkStreamADSBVehicle : public MavlinkStream
}

private:
explicit MavlinkStreamADSBVehicle(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamADSBVehicle(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamADSBVehicle()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] { ORB_ID::transponder_report };

uORB::Subscription _transponder_report_sub{ORB_ID(transponder_report)};

Expand Down
16 changes: 15 additions & 1 deletion src/modules/mavlink/streams/ALTITUDE.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,21 @@ class MavlinkStreamAltitude : public MavlinkStream
}

private:
explicit MavlinkStreamAltitude(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamAltitude(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamAltitude()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[3] {
ORB_ID::vehicle_air_data,
ORB_ID::home_position,
ORB_ID::vehicle_local_position
};

uORB::Subscription _air_data_sub{ORB_ID(vehicle_air_data)};
uORB::Subscription _home_sub{ORB_ID(home_position)};
Expand Down
15 changes: 14 additions & 1 deletion src/modules/mavlink/streams/ATTITUDE.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,20 @@ class MavlinkStreamAttitude : public MavlinkStream
}

private:
explicit MavlinkStreamAttitude(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamAttitude(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamAttitude()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[2] {
ORB_ID::vehicle_attitude,
ORB_ID::vehicle_angular_velocity
};

uORB::Subscription _att_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _angular_velocity_sub{ORB_ID(vehicle_angular_velocity)};
Expand Down
17 changes: 16 additions & 1 deletion src/modules/mavlink/streams/ATTITUDE_QUATERNION.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,22 @@ class MavlinkStreamAttitudeQuaternion : public MavlinkStream
}

private:
explicit MavlinkStreamAttitudeQuaternion(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamAttitudeQuaternion(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamAttitudeQuaternion()
{
_mavlink->unregister_orb_poll(get_id_static());
}


ORB_ID _orbs[3] {
ORB_ID::vehicle_attitude,
ORB_ID::vehicle_angular_velocity,
ORB_ID::vehicle_status
};

uORB::Subscription _att_sub{ORB_ID(vehicle_attitude)};
uORB::Subscription _angular_velocity_sub{ORB_ID(vehicle_angular_velocity)};
Expand Down
16 changes: 15 additions & 1 deletion src/modules/mavlink/streams/ATTITUDE_TARGET.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,21 @@ class MavlinkStreamAttitudeTarget : public MavlinkStream
}

private:
explicit MavlinkStreamAttitudeTarget(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamAttitudeTarget(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamAttitudeTarget()
{
_mavlink->unregister_orb_poll(get_id_static());
}


ORB_ID _orbs[2] {
ORB_ID::vehicle_attitude_setpoint,
ORB_ID::vehicle_rates_setpoint
};

uORB::Subscription _att_sp_sub{ORB_ID(vehicle_attitude_setpoint)};
uORB::Subscription _att_rates_sp_sub{ORB_ID(vehicle_rates_setpoint)};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,25 @@ class MavlinkStreamAutopilotStateForGimbalDevice : public MavlinkStream
}

private:
explicit MavlinkStreamAutopilotStateForGimbalDevice(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamAutopilotStateForGimbalDevice(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamAutopilotStateForGimbalDevice()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[6] {
ORB_ID::estimator_selector_status,
ORB_ID::estimator_status,
ORB_ID::vehicle_attitude,
ORB_ID::vehicle_local_position,
ORB_ID::vehicle_attitude_setpoint,
ORB_ID::vehicle_land_detected
};


uORB::Subscription _estimator_selector_status_sub{ORB_ID(estimator_selector_status)};
uORB::Subscription _estimator_status_sub{ORB_ID(estimator_status)};
Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/BATTERY_STATUS.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,19 @@ class MavlinkStreamBatteryStatus : public MavlinkStream
}

private:
explicit MavlinkStreamBatteryStatus(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamBatteryStatus(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamBatteryStatus()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::battery_status
};

uORB::SubscriptionMultiArray<battery_status_s, battery_status_s::MAX_INSTANCES> _battery_status_subs{ORB_ID::battery_status};

Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/CAMERA_IMAGE_CAPTURED.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,19 @@ class MavlinkStreamCameraImageCaptured : public MavlinkStream
}

private:
explicit MavlinkStreamCameraImageCaptured(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamCameraImageCaptured(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamCameraImageCaptured()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::camera_capture
};

uORB::Subscription _capture_sub{ORB_ID(camera_capture)};

Expand Down
15 changes: 14 additions & 1 deletion src/modules/mavlink/streams/CAMERA_TRIGGER.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,20 @@ class MavlinkStreamCameraTrigger : public MavlinkStream
}

private:
explicit MavlinkStreamCameraTrigger(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamCameraTrigger(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamCameraTrigger()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[2] {
ORB_ID::camera_trigger,
ORB_ID::camera_status
};

uORB::Subscription _camera_trigger_sub{ORB_ID(camera_trigger)};
uORB::Subscription _camera_status_sub{ORB_ID(camera_status)};
Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/COLLISION.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,19 @@ class MavlinkStreamCollision : public MavlinkStream
}

private:
explicit MavlinkStreamCollision(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamCollision(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamCollision()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::collision_report
};

uORB::Subscription _collision_sub{ORB_ID(collision_report)};

Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/COMMAND_LONG.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,19 @@ class MavlinkStreamCommandLong : public MavlinkStream
}

private:
explicit MavlinkStreamCommandLong(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamCommandLong(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamCommandLong()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::vehicle_command
};

uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};

Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/DEBUG.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,19 @@ class MavlinkStreamDebug : public MavlinkStream
}

private:
explicit MavlinkStreamDebug(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamDebug(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamDebug()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::debug_value
};

uORB::Subscription _debug_value_sub{ORB_ID(debug_value)};

Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/DEBUG_FLOAT_ARRAY.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,19 @@ class MavlinkStreamDebugFloatArray : public MavlinkStream
}

private:
explicit MavlinkStreamDebugFloatArray(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamDebugFloatArray(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamDebugFloatArray()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::debug_array
};

uORB::Subscription _debug_array_sub{ORB_ID(debug_array)};

Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/DEBUG_VECT.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,19 @@ class MavlinkStreamDebugVect : public MavlinkStream
}

private:
explicit MavlinkStreamDebugVect(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamDebugVect(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamDebugVect()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::debug_vect
};

uORB::Subscription _debug_sub{ORB_ID(debug_vect)};

Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/DISTANCE_SENSOR.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,19 @@ class MavlinkStreamDistanceSensor : public MavlinkStream
}

private:
explicit MavlinkStreamDistanceSensor(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamDistanceSensor(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamDistanceSensor()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::distance_sensor
};

uORB::SubscriptionMultiArray<distance_sensor_s> _distance_sensor_subs{ORB_ID::distance_sensor};

Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/EFI_STATUS.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,19 @@ class MavlinkStreamEfiStatus : public MavlinkStream
}

private:
explicit MavlinkStreamEfiStatus(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamEfiStatus(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamEfiStatus()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::internal_combustion_engine_status
};

uORB::Subscription _internal_combustion_engine_status_sub{ORB_ID(internal_combustion_engine_status)};

Expand Down
14 changes: 13 additions & 1 deletion src/modules/mavlink/streams/ESC_INFO.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,19 @@ class MavlinkStreamESCInfo : public MavlinkStream
}

private:
explicit MavlinkStreamESCInfo(Mavlink *mavlink) : MavlinkStream(mavlink) {}
explicit MavlinkStreamESCInfo(Mavlink *mavlink) : MavlinkStream(mavlink)
{
mavlink->register_orb_poll(get_id_static(), _orbs, arraySize(_orbs));
}

~MavlinkStreamESCInfo()
{
_mavlink->unregister_orb_poll(get_id_static());
}

ORB_ID _orbs[1] {
ORB_ID::esc_status
};

uORB::Subscription _esc_status_sub{ORB_ID(esc_status)};
uint8_t _number_of_batches{0};
Expand Down
Loading

0 comments on commit aa9e6a0

Please sign in to comment.