Skip to content

Commit

Permalink
doxygen: add high level docs for classes
Browse files Browse the repository at this point in the history
  • Loading branch information
GuillaumeLaine authored and bkueng committed Feb 28, 2024
1 parent cf07120 commit 7c35b25
Show file tree
Hide file tree
Showing 15 changed files with 38 additions and 9 deletions.
2 changes: 1 addition & 1 deletion px4_ros2_cpp/include/px4_ros2/common/requirement_flags.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ namespace px4_ros2
{

/**
* Requirement flags used by modes
* @brief Requirement flags used by modes
*/
struct RequirementFlags
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,9 @@ namespace px4_ros2
* @{
*/

/**
* @brief Provides access to manually input control setpoints
*/
class ManualControlInput
{
public:
Expand Down
2 changes: 1 addition & 1 deletion px4_ros2_cpp/include/px4_ros2/components/mode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ constexpr inline const char * resultToString(Result result) noexcept
}

/**
* Base class for a mode
* @brief Base class for a mode
* \ingroup components
*/
class ModeBase : public Context
Expand Down
2 changes: 1 addition & 1 deletion px4_ros2_cpp/include/px4_ros2/components/mode_executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace px4_ros2
*/

/**
* Base class for a mode executor
* @brief Base class for a mode executor
*/
class ModeExecutorBase
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,9 @@ namespace px4_ros2
*/

/**
* Control one or more extra actuators. It maps to the 'Peripheral Actuator Set' output functions on the PX4 side.
* @brief Provides control of one or more extra actuators.
*
* It maps to the 'Peripheral Actuator Set' output functions on the PX4 side.
* This can be used by a mode independent from the setpoints.
*/
class PeripheralActuatorControls
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ namespace px4_ros2
*/

/**
* Setpoint type for direct actuator control (servos and/or motors)
* @brief Setpoint type for direct actuator control (servos and/or motors)
*/
class DirectActuatorsSetpointType : public SetpointBase
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@ namespace px4_ros2
* @{
*/

/**
* @brief Setpoint type for direct attitude control
*/
class AttitudeSetpointType : public SetpointBase
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,9 @@ namespace px4_ros2
* @{
*/

/**
* @brief Setpoint type for direct rate control
*/
class RatesSetpointType : public SetpointBase
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,11 @@ namespace px4_ros2
* @{
*/

/**
* @brief Setpoint type for trajectory control
*
* Control entries must not be contradicting.
*/
class TrajectorySetpointType : public SetpointBase
{
public:
Expand Down
6 changes: 6 additions & 0 deletions px4_ros2_cpp/include/px4_ros2/control/setpoint_types/goto.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,9 @@ namespace px4_ros2
* @{
*/

/**
* @brief Setpoint type for smooth position and heading control
*/
class GotoSetpointType : public SetpointBase
{
public:
Expand Down Expand Up @@ -54,6 +57,9 @@ class GotoSetpointType : public SetpointBase
_goto_setpoint_pub;
};

/**
* @brief Setpoint type for smooth global position and heading control
*/
class GotoGlobalSetpointType
{
public:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,20 @@

namespace px4_ros2
{

/**
* @brief Thrown to report invalid arguments to measurement interface
*/
class NavigationInterfaceInvalidArgument : public std::invalid_argument
{
public:
explicit NavigationInterfaceInvalidArgument(const std::string & message)
: std::invalid_argument("PX4 ROS2 navigation interface: invalid argument: " + message) {}
};

/**
* @brief Base class for position measurement interface
*/
class PositionMeasurementInterfaceBase : public Context
{
public:
Expand Down
2 changes: 1 addition & 1 deletion px4_ros2_cpp/include/px4_ros2/odometry/attitude.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ namespace px4_ros2
*/

/**
* Provides access to the vehicle's attitude estimate
* @brief Provides access to the vehicle's attitude estimate
*/
class OdometryAttitude : public Subscription<px4_msgs::msg::VehicleAttitude>
{
Expand Down
2 changes: 1 addition & 1 deletion px4_ros2_cpp/include/px4_ros2/odometry/global_position.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ namespace px4_ros2
*/

/**
* Provides access to the vehicle's global position estimate
* @brief Provides access to the vehicle's global position estimate
*/
class OdometryGlobalPosition : public Subscription<px4_msgs::msg::VehicleGlobalPosition>
{
Expand Down
2 changes: 1 addition & 1 deletion px4_ros2_cpp/include/px4_ros2/odometry/local_position.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ namespace px4_ros2
*/

/**
* Provides access to the vehicle's local position estimate
* @brief Provides access to the vehicle's local position estimate
*/
class OdometryLocalPosition : public Subscription<px4_msgs::msg::VehicleLocalPosition>
{
Expand Down
2 changes: 1 addition & 1 deletion px4_ros2_cpp/include/px4_ros2/odometry/subscription.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@ namespace px4_ros2
*/

/**
* Provides a subscription to arbitrary ROS topics.
* @brief Provides a subscription to arbitrary ROS topics.
*/
template<typename RosMessageType>
class Subscription
Expand Down

0 comments on commit 7c35b25

Please sign in to comment.