Skip to content

Commit

Permalink
naming: changed naming to constently be px4-ros2
Browse files Browse the repository at this point in the history
  • Loading branch information
ThomasDebrunner committed Oct 20, 2023
1 parent 5ab3d1a commit 46ee503
Show file tree
Hide file tree
Showing 62 changed files with 301 additions and 271 deletions.
4 changes: 2 additions & 2 deletions .github/workflows/build_and_test.yml
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ jobs:
},
"test": {
"packages-select-regex": [
"px4_sdk_cpp"
"px4_ros2_cpp"
],
"ctest-args": [
"-R", "unit_tests"
Expand All @@ -55,5 +55,5 @@ jobs:
ROS_WS_DIR="$(readlink -f ${{ steps.ros-build.outputs.ros-workspace-directory-name }})"
cd "$ROS_WS_DIR"
cd src
cd $(find -name px4_sdk|head -1) # the path looks like this: 'src/zlrido15uw/px4_sdk'
cd $(find -name px4_ros2|head -1) # the path looks like this: 'src/zlrido15uw/px4_ros2'
./scripts/run-clang-tidy-on-project.sh "$ROS_WS_DIR"/build
8 changes: 8 additions & 0 deletions .idea/.gitignore

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

6 changes: 6 additions & 0 deletions .idea/misc.xml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

8 changes: 8 additions & 0 deletions .idea/modules.xml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

2 changes: 2 additions & 0 deletions .idea/px4-ros2-interface-lib.iml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

6 changes: 6 additions & 0 deletions .idea/vcs.xml

Some generated files are not rendered by default. Learn more about how customized files appear on GitHub.

12 changes: 6 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@ A mode can send different types of setpoints, ranging from high-level navigation

## Compatibility with PX4
The library interacts with PX4 by using its uORB messages, and thus requires a matching set of message definitions on the ROS 2 side.
Compatibility is only guaranteed if using latest `main` on the PX4 and SDK/px4_msgs side. This might change in the future.
Compatibility is only guaranteed if using latest `main` on the PX4 and px4_ros2/px4_msgs side. This might change in the future.

The SDK checks for message compatibility on startup when registering a mode.
`ALL_PX4_SDK_MESSAGES` defines the set of checked messages. If you use other messages, you can check them using:
The library checks for message compatibility on startup when registering a mode.
`ALL_PX4_ROS2_MESSAGES` defines the set of checked messages. If you use other messages, you can check them using:
```c++
if (!px4_sdk::messageCompatibilityCheck(node, {{"/fmu/in/vehicle_rates_setpoint"}})) {
if (!px4_ros2::messageCompatibilityCheck(node, {{"/fmu/in/vehicle_rates_setpoint"}})) {
throw std::runtime_error("Messages incompatible");
}
```
Expand All @@ -37,12 +37,12 @@ Make sure you have the ROS workspace sourced.
#### Unit tests
You can either run the unit tests through colcon:
```shell
colcon test --packages-select px4_sdk_cpp --ctest-args -R unit_tests
colcon test --packages-select px4_ros2_cpp --ctest-args -R unit_tests
colcon test-result --verbose
```
Or directly from the build directory, which allows to filter by individual tests:
```shell
./build/px4_sdk_cpp/px4_sdk_cpp_unit_tests --gtest_filter='xy*'
./build/px4_ros2_cpp/px4_ros2_cpp_unit_tests --gtest_filter='xy*'
```

#### Linters (code formatting etc)
Expand Down
4 changes: 2 additions & 2 deletions examples/cpp/modes/manual/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@ find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(px4_sdk_cpp REQUIRED)
find_package(px4_ros2_cpp REQUIRED)

include_directories(include ${Eigen3_INCLUDE_DIRS})
add_executable(example_mode_manual
src/main.cpp)
ament_target_dependencies(example_mode_manual Eigen3 px4_sdk_cpp rclcpp)
ament_target_dependencies(example_mode_manual Eigen3 px4_ros2_cpp rclcpp)

install(TARGETS
example_mode_manual
Expand Down
26 changes: 13 additions & 13 deletions examples/cpp/modes/manual/include/mode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
****************************************************************************/
#pragma once

#include <px4_sdk/components/mode.hpp>
#include <px4_sdk/control/setpoint_types/rates.hpp>
#include <px4_sdk/control/setpoint_types/attitude.hpp>
#include <px4_sdk/control/offboard_actuators.hpp>
#include <px4_ros2/components/mode.hpp>
#include <px4_ros2/control/setpoint_types/rates.hpp>
#include <px4_ros2/control/setpoint_types/attitude.hpp>
#include <px4_ros2/control/offboard_actuators.hpp>

#include <Eigen/Eigen>

Expand Down Expand Up @@ -38,16 +38,16 @@ static inline Eigen::Quaternionf quaternionFromEuler(
return quaternionFromEuler(Eigen::Vector3f(roll, pitch, yaw));
}

class FlightModeTest : public px4_sdk::ModeBase
class FlightModeTest : public px4_ros2::ModeBase
{
public:
explicit FlightModeTest(rclcpp::Node & node)
: ModeBase(node, kName)
{
_manual_control_input = std::make_shared<px4_sdk::ManualControlInput>(*this);
_rates_setpoint = std::make_shared<px4_sdk::RatesSetpointType>(*this);
_attitude_setpoint = std::make_shared<px4_sdk::AttitudeSetpointType>(*this);
_offboard_actuator_controls = std::make_shared<px4_sdk::OffboardActuatorControls>(*this);
_manual_control_input = std::make_shared<px4_ros2::ManualControlInput>(*this);
_rates_setpoint = std::make_shared<px4_ros2::RatesSetpointType>(*this);
_attitude_setpoint = std::make_shared<px4_ros2::AttitudeSetpointType>(*this);
_offboard_actuator_controls = std::make_shared<px4_ros2::OffboardActuatorControls>(*this);
}

void onActivate() override {}
Expand Down Expand Up @@ -87,10 +87,10 @@ class FlightModeTest : public px4_sdk::ModeBase
}

private:
std::shared_ptr<px4_sdk::ManualControlInput> _manual_control_input;
std::shared_ptr<px4_sdk::RatesSetpointType> _rates_setpoint;
std::shared_ptr<px4_sdk::AttitudeSetpointType> _attitude_setpoint;
std::shared_ptr<px4_sdk::OffboardActuatorControls> _offboard_actuator_controls;
std::shared_ptr<px4_ros2::ManualControlInput> _manual_control_input;
std::shared_ptr<px4_ros2::RatesSetpointType> _rates_setpoint;
std::shared_ptr<px4_ros2::AttitudeSetpointType> _attitude_setpoint;
std::shared_ptr<px4_ros2::OffboardActuatorControls> _offboard_actuator_controls;
float _yaw{0.F};
};

Expand Down
2 changes: 1 addition & 1 deletion examples/cpp/modes/manual/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<build_depend>rclcpp</build_depend>
<build_export_depend>eigen</build_export_depend>

<depend>px4_sdk_cpp</depend>
<depend>px4_ros2_cpp</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
4 changes: 2 additions & 2 deletions examples/cpp/modes/mode_with_executor/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@ find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(px4_sdk_cpp REQUIRED)
find_package(px4_ros2_cpp REQUIRED)

include_directories(include ${Eigen3_INCLUDE_DIRS})
add_executable(example_mode_with_executor
src/main.cpp)
ament_target_dependencies(example_mode_with_executor Eigen3 px4_sdk_cpp rclcpp)
ament_target_dependencies(example_mode_with_executor Eigen3 px4_ros2_cpp rclcpp)

install(TARGETS
example_mode_with_executor
Expand Down
38 changes: 19 additions & 19 deletions examples/cpp/modes/mode_with_executor/include/mode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
****************************************************************************/
#pragma once

#include <px4_sdk/components/mode.hpp>
#include <px4_sdk/components/mode_executor.hpp>
#include <px4_sdk/components/wait_for_fmu.hpp>
#include <px4_sdk/control/setpoint_types/trajectory.hpp>
#include <px4_ros2/components/mode.hpp>
#include <px4_ros2/components/mode_executor.hpp>
#include <px4_ros2/components/wait_for_fmu.hpp>
#include <px4_ros2/control/setpoint_types/trajectory.hpp>

#include <rclcpp/rclcpp.hpp>

Expand All @@ -18,13 +18,13 @@ using namespace std::chrono_literals; // NOLINT
static const std::string kName = "Autonomous Executor";
static const std::string kNodeName = "example_mode_with_executor";

class FlightModeTest : public px4_sdk::ModeBase
class FlightModeTest : public px4_ros2::ModeBase
{
public:
explicit FlightModeTest(rclcpp::Node & node)
: ModeBase(node, Settings{kName, false})
{
_trajectory_setpoint = std::make_shared<px4_sdk::TrajectorySetpointType>(*this);
_trajectory_setpoint = std::make_shared<px4_ros2::TrajectorySetpointType>(*this);
}

~FlightModeTest() override = default;
Expand All @@ -41,7 +41,7 @@ class FlightModeTest : public px4_sdk::ModeBase
const rclcpp::Time now = node().get_clock()->now();

if (now - _activation_time > 5s) {
completed(px4_sdk::Result::Success);
completed(px4_ros2::Result::Success);
return;
}

Expand All @@ -52,14 +52,14 @@ class FlightModeTest : public px4_sdk::ModeBase

private:
rclcpp::Time _activation_time{};
std::shared_ptr<px4_sdk::TrajectorySetpointType> _trajectory_setpoint;
std::shared_ptr<px4_ros2::TrajectorySetpointType> _trajectory_setpoint;
};

class ModeExecutorTest : public px4_sdk::ModeExecutorBase
class ModeExecutorTest : public px4_ros2::ModeExecutorBase
{
public:
ModeExecutorTest(rclcpp::Node & node, px4_sdk::ModeBase & owned_mode)
: ModeExecutorBase(node, px4_sdk::ModeExecutorBase::Settings{}, owned_mode),
ModeExecutorTest(rclcpp::Node & node, px4_ros2::ModeBase & owned_mode)
: ModeExecutorBase(node, px4_ros2::ModeExecutorBase::Settings{}, owned_mode),
_node(node)
{
}
Expand All @@ -75,16 +75,16 @@ class ModeExecutorTest : public px4_sdk::ModeExecutorBase

void onActivate() override
{
runState(State::TakingOff, px4_sdk::Result::Success);
runState(State::TakingOff, px4_ros2::Result::Success);
}

void onDeactivate(DeactivateReason reason) override
{
}

void runState(State state, px4_sdk::Result previous_result)
void runState(State state, px4_ros2::Result previous_result)
{
if (previous_result != px4_sdk::Result::Success) {
if (previous_result != px4_ros2::Result::Success) {
RCLCPP_ERROR(
_node.get_logger(), "State %i: previous state failed: %s", (int)state,
resultToString(previous_result));
Expand All @@ -98,23 +98,23 @@ class ModeExecutorTest : public px4_sdk::ModeExecutorBase
break;

case State::TakingOff:
takeoff([this](px4_sdk::Result result) {runState(State::MyMode, result);});
takeoff([this](px4_ros2::Result result) {runState(State::MyMode, result);});
break;

case State::MyMode:
scheduleMode(
ownedMode().id(), [this](px4_sdk::Result result) {
ownedMode().id(), [this](px4_ros2::Result result) {
runState(State::RTL, result);
});
break;

case State::RTL:
rtl([this](px4_sdk::Result result) {runState(State::WaitUntilDisarmed, result);});
rtl([this](px4_ros2::Result result) {runState(State::WaitUntilDisarmed, result);});
break;

case State::WaitUntilDisarmed:
waitUntilDisarmed(
[this](px4_sdk::Result result) {
[this](px4_ros2::Result result) {
RCLCPP_INFO(_node.get_logger(), "All states complete (%s)", resultToString(result));
});
break;
Expand All @@ -140,7 +140,7 @@ class TestNode : public rclcpp::Node
rcutils_reset_error();
}

if (!px4_sdk::waitForFMU(*this)) {
if (!px4_ros2::waitForFMU(*this)) {
throw std::runtime_error("No message from FMU");
}

Expand Down
2 changes: 1 addition & 1 deletion examples/cpp/modes/mode_with_executor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<build_depend>rclcpp</build_depend>
<build_export_depend>eigen</build_export_depend>

<depend>px4_sdk_cpp</depend>
<depend>px4_ros2_cpp</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
4 changes: 2 additions & 2 deletions examples/cpp/modes/rtl_replacement/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,12 @@ find_package(eigen3_cmake_module REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(px4_sdk_cpp REQUIRED)
find_package(px4_ros2_cpp REQUIRED)

include_directories(include ${Eigen3_INCLUDE_DIRS})
add_executable(example_mode_rtl
src/main.cpp)
ament_target_dependencies(example_mode_rtl Eigen3 px4_sdk_cpp rclcpp)
ament_target_dependencies(example_mode_rtl Eigen3 px4_ros2_cpp rclcpp)

install(TARGETS
example_mode_rtl
Expand Down
16 changes: 8 additions & 8 deletions examples/cpp/modes/rtl_replacement/include/mode.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,10 @@
****************************************************************************/
#pragma once

#include <px4_sdk/components/mode.hpp>
#include <px4_sdk/components/health_and_arming_checks.hpp>
#include <px4_sdk/components/mode_executor.hpp>
#include <px4_sdk/control/setpoint_types/trajectory.hpp>
#include <px4_ros2/components/mode.hpp>
#include <px4_ros2/components/health_and_arming_checks.hpp>
#include <px4_ros2/components/mode_executor.hpp>
#include <px4_ros2/control/setpoint_types/trajectory.hpp>
#include <px4_msgs/msg/vehicle_land_detected.hpp>

#include <rclcpp/rclcpp.hpp>
Expand All @@ -19,7 +19,7 @@ using namespace std::chrono_literals; // NOLINT
static const std::string kName = "Custom RTL";
static const std::string kNodeName = "example_mode_rtl";

class FlightModeTest : public px4_sdk::ModeBase
class FlightModeTest : public px4_ros2::ModeBase
{
public:
explicit FlightModeTest(rclcpp::Node & node)
Expand All @@ -30,7 +30,7 @@ class FlightModeTest : public px4_sdk::ModeBase
[this](px4_msgs::msg::VehicleLandDetected::UniquePtr msg) {
_landed = msg->landed;
});
_trajectory_setpoint = std::make_shared<px4_sdk::TrajectorySetpointType>(*this);
_trajectory_setpoint = std::make_shared<px4_ros2::TrajectorySetpointType>(*this);

modeRequirements().home_position = true;
}
Expand All @@ -45,7 +45,7 @@ class FlightModeTest : public px4_sdk::ModeBase
void updateSetpoint(float dt_s) override
{
if (_landed) {
completed(px4_sdk::Result::Success);
completed(px4_ros2::Result::Success);
return;
}

Expand All @@ -57,7 +57,7 @@ class FlightModeTest : public px4_sdk::ModeBase
rclcpp::Time _activation_time{};
bool _landed{true};
rclcpp::Subscription<px4_msgs::msg::VehicleLandDetected>::SharedPtr _vehicle_land_detected_sub;
std::shared_ptr<px4_sdk::TrajectorySetpointType> _trajectory_setpoint;
std::shared_ptr<px4_ros2::TrajectorySetpointType> _trajectory_setpoint;
};

class TestNode : public rclcpp::Node
Expand Down
2 changes: 1 addition & 1 deletion examples/cpp/modes/rtl_replacement/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
<build_depend>rclcpp</build_depend>
<build_export_depend>eigen</build_export_depend>

<depend>px4_sdk_cpp</depend>
<depend>px4_ros2_cpp</depend>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
Expand Down
Loading

0 comments on commit 46ee503

Please sign in to comment.