Skip to content

Commit

Permalink
apply review suggestions
Browse files Browse the repository at this point in the history
  • Loading branch information
GuillaumeLaine committed Oct 31, 2024
1 parent 7dba422 commit ac8a945
Show file tree
Hide file tree
Showing 11 changed files with 14 additions and 137 deletions.
5 changes: 0 additions & 5 deletions px4_ros2_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -80,11 +80,6 @@ add_library(px4_ros2_cpp
src/odometry/angular_velocity.cpp
src/utils/geodesic.cpp
src/utils/map_projection_impl.cpp
src/vehicle_state/battery.cpp
src/vehicle_state/home_position.cpp
src/vehicle_state/land_detected.cpp
src/vehicle_state/vehicle_status.cpp
src/vehicle_state/vtol_status.cpp
)
ament_target_dependencies(px4_ros2_cpp ament_index_cpp Eigen3 rclcpp px4_msgs)

Expand Down
3 changes: 2 additions & 1 deletion px4_ros2_cpp/include/px4_ros2/vehicle_state/battery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,8 @@ namespace px4_ros2
class Battery : public Subscription<px4_msgs::msg::BatteryStatus>
{
public:
explicit Battery(Context & context);
explicit Battery(Context & context)
: Subscription<px4_msgs::msg::BatteryStatus>(context, "fmu/out/battery_status") {}

/**
* @brief Get the vehicle's battery voltage.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,8 @@ namespace px4_ros2
class HomePosition : public Subscription<px4_msgs::msg::HomePosition>
{
public:
explicit HomePosition(Context & context);
explicit HomePosition(Context & context)
: Subscription<px4_msgs::msg::HomePosition>(context, "fmu/out/home_position") {}

/**
* @brief Get the vehicle's home position in local coordinates.
Expand Down
41 changes: 4 additions & 37 deletions px4_ros2_cpp/include/px4_ros2/vehicle_state/land_detected.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,50 +23,17 @@ namespace px4_ros2
class LandDetected : public Subscription<px4_msgs::msg::VehicleLandDetected>
{
public:
explicit LandDetected(Context & context);
explicit LandDetected(Context & context)
: Subscription<px4_msgs::msg::VehicleLandDetected>(context, "fmu/out/vehicle_land_detected") {}

/**
* @brief Check if vehicle has made ground contact, but is not landed (stage 1).
*
* @return true if ground contact, false otherwise
*/
bool groundContact() const
{
const px4_msgs::msg::VehicleLandDetected & land_detected = last();
return land_detected.ground_contact;
}

/**
* @brief Check if vehicle has maybe landed (stage 2).
*
* @return true if maybe landed, false otherwise
*/
bool maybeLanded() const
{
const px4_msgs::msg::VehicleLandDetected & land_detected = last();
return land_detected.maybe_landed;
}

/**
* @brief Check if vehicle is landed on the ground (stage 3).
* @brief Check if vehicle is landed on the ground.
*
* @return true if landed, false otherwise
*/
bool landed() const
{
const px4_msgs::msg::VehicleLandDetected & land_detected = last();
return land_detected.landed;
}

/**
* @brief Check if vehicle is descending.
*
* @return true if descending, false otherwise
*/
bool inDescend() const
{
const px4_msgs::msg::VehicleLandDetected & land_detected = last();
return land_detected.in_descend;
return last().landed;
}

};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ namespace px4_ros2
class VehicleStatus : public Subscription<px4_msgs::msg::VehicleStatus>
{
public:
explicit VehicleStatus(Context & context);
explicit VehicleStatus(Context & context)
: Subscription<px4_msgs::msg::VehicleStatus>(context, "fmu/out/vehicle_status") {}

/**
* @brief Get the vehicle's arming status.
Expand All @@ -39,6 +40,7 @@ class VehicleStatus : public Subscription<px4_msgs::msg::VehicleStatus>
* @brief Get the vehicle's current active flight mode.
*
* @return the int value describing the mode
* @see navigation state values: https://github.com/PX4/PX4-Autopilot/blob/v1.15.0/msg/VehicleStatus.msg#L34-L65
*/
uint8_t navState() const
{
Expand Down
5 changes: 3 additions & 2 deletions px4_ros2_cpp/include/px4_ros2/vehicle_state/vtol_status.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,10 +23,11 @@ namespace px4_ros2
class VtolStatus : public Subscription<px4_msgs::msg::VtolVehicleStatus>
{
public:
explicit VtolStatus(Context & context);
explicit VtolStatus(Context & context)
: Subscription<px4_msgs::msg::VtolVehicleStatus>(context, "fmu/out/vtol_vehicle_status") {}

/**
* @brief Check if VTOL is in an undefined state.
* @brief Check if vehicle is in an undefined state. This indicates the vehicle is not a VTOL.
*
* @return true if undefined state, false otherwise.
*/
Expand Down
18 changes: 0 additions & 18 deletions px4_ros2_cpp/src/vehicle_state/battery.cpp

This file was deleted.

18 changes: 0 additions & 18 deletions px4_ros2_cpp/src/vehicle_state/home_position.cpp

This file was deleted.

18 changes: 0 additions & 18 deletions px4_ros2_cpp/src/vehicle_state/land_detected.cpp

This file was deleted.

18 changes: 0 additions & 18 deletions px4_ros2_cpp/src/vehicle_state/vehicle_status.cpp

This file was deleted.

18 changes: 0 additions & 18 deletions px4_ros2_cpp/src/vehicle_state/vtol_status.cpp

This file was deleted.

0 comments on commit ac8a945

Please sign in to comment.