Skip to content

Commit

Permalink
TEST: add classes to groups for doxygen
Browse files Browse the repository at this point in the history
  • Loading branch information
bkueng committed Nov 28, 2023
1 parent f494d3f commit 72c4b7c
Show file tree
Hide file tree
Showing 5 changed files with 33 additions and 0 deletions.
4 changes: 4 additions & 0 deletions px4_ros2_cpp/include/px4_ros2/components/mode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,9 @@ struct RegistrationSettings;
namespace px4_ros2
{

/** \addtogroup Components
* @{
*/
enum class Result
{
Success = 0,
Expand Down Expand Up @@ -202,4 +205,5 @@ class ModeBase : public Context
std::vector<SetpointBase *> _new_setpoint_types; ///< This stores new setpoints during initialization, until registration
};

/** @}*/
} // namespace px4_ros2
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,14 @@
namespace px4_ros2
{

/** \addtogroup Control
* @{
*/

/** @defgroup Setpoints Setpoint Types
* @ingroup Control
*/

/**
* Control 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.
Expand Down Expand Up @@ -43,4 +51,5 @@ class PeripheralActuatorControls
rclcpp::Time _last_update{};
};

/** @}*/
} /* namespace px4_ros2 */
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,9 @@
namespace px4_ros2
{

/** \addtogroup Setpoints
* @{
*/
class DirectActuatorsSetpointType : public SetpointBase
{
public:
Expand Down Expand Up @@ -48,4 +51,5 @@ class DirectActuatorsSetpointType : public SetpointBase
rclcpp::Publisher<px4_msgs::msg::ActuatorServos>::SharedPtr _actuator_servos_pub;
};

/** @}*/
} /* namespace px4_ros2 */
8 changes: 8 additions & 0 deletions px4_ros2_cpp/include/px4_ros2/odometry/global_position.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,18 @@
#include <Eigen/Eigen>
#include <px4_ros2/common/context.hpp>


using namespace std::chrono_literals; // NOLINT

namespace px4_ros2
{

/** \addtogroup Odometry
* @{
*/
/**
* Provides access to the vehicle's global position estimate
*/
class OdometryGlobalPosition
{
public:
Expand All @@ -38,4 +45,5 @@ class OdometryGlobalPosition
rclcpp::Time _last_vehicle_global_position;
};

/** @}*/
} /* namespace px4_ros2 */
8 changes: 8 additions & 0 deletions px4_ros2_cpp/include/px4_ros2/odometry/local_position.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,16 @@
#include <Eigen/Eigen>
#include <px4_ros2/common/context.hpp>


namespace px4_ros2
{

/** \addtogroup Odometry
* @{
*/
/**
* Provides access to the vehicle's local position estimate
*/
class OdometryLocalPosition
{
public:
Expand Down Expand Up @@ -57,4 +64,5 @@ class OdometryLocalPosition
px4_msgs::msg::VehicleLocalPosition _vehicle_local_position;
};

/** @}*/
} /* namespace px4_ros2 */

0 comments on commit 72c4b7c

Please sign in to comment.