Skip to content

Commit f88a7c8

Browse files
authored
Merge pull request #4 from enwaytech/lyrical
Migrate to Lyrical
2 parents 1942505 + 76f32d8 commit f88a7c8

27 files changed

+165
-162
lines changed

.github/workflows/lint.yml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ jobs:
77
name: ament_${{ matrix.linter }}
88
runs-on: ubuntu-latest
99
container:
10-
image: rostooling/setup-ros-docker:ubuntu-noble-ros-jazzy-ros-base-latest
10+
image: ghcr.io/ros-tooling/setup-ros-docker/setup-ros-docker-ubuntu-noble-ros-rolling-ros-base:master
1111
strategy:
1212
fail-fast: false
1313
matrix:
@@ -17,7 +17,7 @@ jobs:
1717
- uses: ros-tooling/[email protected]
1818
with:
1919
linter: ${{ matrix.linter }}
20-
distribution: jazzy
20+
distribution: rolling
2121
package-name: |
2222
opennav_coverage
2323
opennav_coverage_bt

.github/workflows/test.yml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,18 +12,18 @@ jobs:
1212
ROS_DISTRO: ${{ matrix.ros_distro }}
1313
RMW_IMPLEMENTATION: rmw_cyclonedds_cpp
1414
container:
15-
image: rostooling/setup-ros-docker:ubuntu-noble-latest
15+
image: ghcr.io/ros-tooling/setup-ros-docker/setup-ros-docker-ubuntu-noble-ros-rolling-ros-base:master
1616
strategy:
1717
fail-fast: false
1818
matrix:
19-
ros_distro: [jazzy]
19+
ros_distro: [rolling]
2020
steps:
2121
- uses: actions/checkout@v2
2222
- name: Install Cyclone DDS
2323
run: sudo apt install ros-${{ matrix.ros_distro }}-rmw-cyclonedds-cpp -y
2424
- name: Build and run tests
2525
id: action-ros-ci
26-
uses: ros-tooling/action-ros-ci@v0.3
26+
uses: ros-tooling/action-ros-ci@v0.4
2727
with:
2828
import-token: ${{ secrets.GITHUB_TOKEN }}
2929
target-ros2-distro: ${{ matrix.ros_distro }}

README.md

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -20,7 +20,7 @@ This server exposes all of the features of Fields2Cover as a Lifecycle-Component
2020

2121
- `opennav_coverage_navigator`: Contains the BT Navigator plugin exposing `NavigateCompleteCoverage` action server analog to `NavigateToPose` and `NavigateThroughPoses`.
2222

23-
- `opennav_coverage_demo`: Contains an example launch and python node to trigger the coverage planner for a demonstration of the Navigator Plugin, Server, BT nodes, XML, and such.
23+
- `opennav_coverage_demo`: Contains an example launch and python node to trigger the coverage planner for a demonstration of the Navigator Plugin, Server, BT nodes, XML, and such.
2424

2525
Fields2Cover is a living library with new features planned to be added (for example those discussed in a [Nav2 integration ticket](https://github.com/Fields2Cover/Fields2Cover/issues/73)). As such, as new F2C capabilities are created, they will be welcome for integration here. If you see anything missing, please let us know or submit a PR to expose it!
2626

@@ -61,7 +61,7 @@ The result returns a `result.nav_path` -- which is a `nav_msgs/Path` containing
6161

6262
It also returns an error code, if any error occurred and the total planning time for metrics analysis.
6363

64-
Note that `SwathMode` settings are to be paired with the `opennav_coverage` server with polygons, while the `RowSwathMode` settings are to be paired with the `opennav_row_coverage` server based on annotated rows.
64+
Note that `SwathMode` settings are to be paired with the `opennav_coverage` server with polygons, while the `RowSwathMode` settings are to be paired with the `opennav_row_coverage` server based on annotated rows.
6565

6666
### NavigateCompleteCoverage
6767

@@ -82,7 +82,6 @@ The complete set of options are exposed as both dynamic parameters and through t
8282

8383
| Parameter | Description | Type |
8484
|------------------------------|------------------------------------------------|--------|
85-
| action_server_result_timeout | Action server result holding timeout (s) | double |
8685
| coordinates_in_cartesian_frame | Whether incoming requests are in cartesian or GPS coordinates | bool |
8786
| robot_width | Robots width (m) | double |
8887
| operation_width | Width of implement or task for coverage | double |
@@ -146,7 +145,7 @@ N/A
146145

147146
#### A Quick Note On Skipping
148147

149-
Rows(r) and swaths(s) are numbered as such. r1, s1, r2, s2, .... rN-1, sN-1, rN.
148+
Rows(r) and swaths(s) are numbered as such. r1, s1, r2, s2, .... rN-1, sN-1, rN.
150149
In order to skip particular rows the 'opennav_coverage_msgs/RowSwathMode' provides 'skip_ids'
151150
to be populated. For example, if the skip ids were set to {1, 3} for five rows the output would be the following: s2, s4.
152151

@@ -156,7 +155,7 @@ As noted about `opennav_row_coverage` provides three ways to compute swaths whic
156155

157156
The `CENTER` generator iterates through each row, calculating a center between consecutive rows.
158157

159-
The `OFFSET` generator iterates through each row, calculating a relative offset between consecutive rows.
158+
The `OFFSET` generator iterates through each row, calculating a relative offset between consecutive rows.
160159

161160
The `SWATHSAREROWS` generator iterates through each row and uses that row as the swath.
162161

opennav_coverage/include/opennav_coverage/coverage_server.hpp

Lines changed: 11 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -21,9 +21,9 @@
2121
#include "fields2cover.h" // NOLINT
2222

2323
#include "rclcpp/rclcpp.hpp"
24-
#include "nav2_util/lifecycle_node.hpp"
25-
#include "nav2_util/node_utils.hpp"
26-
#include "nav2_util/simple_action_server.hpp"
24+
#include "nav2_ros_common/lifecycle_node.hpp"
25+
#include "nav2_ros_common/node_utils.hpp"
26+
#include "nav2_ros_common/simple_action_server.hpp"
2727
#include "opennav_coverage/headland_generator.hpp"
2828
#include "opennav_coverage/swath_generator.hpp"
2929
#include "opennav_coverage/route_generator.hpp"
@@ -37,10 +37,10 @@ namespace opennav_coverage
3737
* @brief An action server which implements highly reconfigurable complete
3838
* coverage planning using the Fields2Cover library
3939
*/
40-
class CoverageServer : public nav2_util::LifecycleNode
40+
class CoverageServer : public nav2::LifecycleNode
4141
{
4242
public:
43-
using ActionServer = nav2_util::SimpleActionServer<ComputeCoveragePath>;
43+
using ActionServer = nav2::SimpleActionServer<ComputeCoveragePath>;
4444

4545
/**
4646
* @brief A constructor for opennav_coverage::CoverageServer
@@ -79,35 +79,35 @@ class CoverageServer : public nav2_util::LifecycleNode
7979
* @param state Reference to LifeCycle node state
8080
* @return SUCCESS or FAILURE
8181
*/
82-
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
82+
nav2::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
8383

8484
/**
8585
* @brief Activate member variables
8686
* @param state Reference to LifeCycle node state
8787
* @return SUCCESS or FAILURE
8888
*/
89-
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
89+
nav2::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
9090

9191
/**
9292
* @brief Deactivate member variables
9393
* @param state Reference to LifeCycle node state
9494
* @return SUCCESS or FAILURE
9595
*/
96-
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
96+
nav2::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
9797

9898
/**
9999
* @brief Reset member variables
100100
* @param state Reference to LifeCycle node state
101101
* @return SUCCESS or FAILURE
102102
*/
103-
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
103+
nav2::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
104104

105105
/**
106106
* @brief Called when in shutdown state
107107
* @param state Reference to LifeCycle node state
108108
* @return SUCCESS or FAILURE
109109
*/
110-
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
110+
nav2::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
111111

112112
/**
113113
* @brief Callback executed when a parameter change is detected
@@ -120,7 +120,7 @@ class CoverageServer : public nav2_util::LifecycleNode
120120
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
121121
std::mutex dynamic_params_lock_;
122122

123-
std::unique_ptr<ActionServer> action_server_;
123+
typename ActionServer::SharedPtr action_server_;
124124

125125
std::unique_ptr<RobotParams> robot_params_;
126126
std::unique_ptr<HeadlandGenerator> headland_gen_;

opennav_coverage/include/opennav_coverage/headland_generator.hpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,8 @@
2121
#include "fields2cover.h" // NOLINT
2222

2323
#include "rclcpp/rclcpp.hpp"
24-
#include "nav2_util/lifecycle_node.hpp"
25-
#include "nav2_util/node_utils.hpp"
24+
#include "nav2_ros_common/lifecycle_node.hpp"
25+
#include "nav2_ros_common/node_utils.hpp"
2626
#include "opennav_coverage_msgs/msg/headland_mode.hpp"
2727
#include "opennav_coverage/utils.hpp"
2828
#include "opennav_coverage/types.hpp"
@@ -45,13 +45,13 @@ class HeadlandGenerator
4545
{
4646
logger_ = node->get_logger();
4747

48-
nav2_util::declare_parameter_if_not_declared(
48+
nav2::declare_parameter_if_not_declared(
4949
node, "default_headland_type", rclcpp::ParameterValue("CONSTANT"));
5050
std::string type_str = node->get_parameter("default_headland_type").as_string();
5151
default_type_ = toType(type_str);
5252
default_generator_ = createGenerator(default_type_);
5353

54-
nav2_util::declare_parameter_if_not_declared(
54+
nav2::declare_parameter_if_not_declared(
5555
node, "default_headland_width", rclcpp::ParameterValue(2.0));
5656
default_headland_width_ = node->get_parameter("default_headland_width").as_double();
5757
}

opennav_coverage/include/opennav_coverage/path_generator.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,8 @@
2222
#include "fields2cover.h" // NOLINT
2323

2424
#include "rclcpp/rclcpp.hpp"
25-
#include "nav2_util/lifecycle_node.hpp"
26-
#include "nav2_util/node_utils.hpp"
25+
#include "nav2_ros_common/lifecycle_node.hpp"
26+
#include "nav2_ros_common/node_utils.hpp"
2727
#include "opennav_coverage_msgs/msg/path_mode.hpp"
2828
#include "opennav_coverage/utils.hpp"
2929
#include "opennav_coverage/types.hpp"
@@ -48,17 +48,17 @@ class PathGenerator
4848
logger_ = node->get_logger();
4949
robot_params_ = robot_params;
5050

51-
nav2_util::declare_parameter_if_not_declared(
51+
nav2::declare_parameter_if_not_declared(
5252
node, "default_path_type", rclcpp::ParameterValue("DUBIN"));
5353
std::string type_str = node->get_parameter("default_path_type").as_string();
5454
default_type_ = toType(type_str);
5555

56-
nav2_util::declare_parameter_if_not_declared(
56+
nav2::declare_parameter_if_not_declared(
5757
node, "default_path_continuity_type", rclcpp::ParameterValue("CONTINUOUS"));
5858
std::string type_cont_str = node->get_parameter("default_path_continuity_type").as_string();
5959
default_continuity_type_ = toContinuityType(type_cont_str);
6060

61-
nav2_util::declare_parameter_if_not_declared(
61+
nav2::declare_parameter_if_not_declared(
6262
node, "default_turn_point_distance", rclcpp::ParameterValue(0.1));
6363
default_turn_point_distance_ = node->get_parameter("default_turn_point_distance").as_double();
6464

opennav_coverage/include/opennav_coverage/robot_params.hpp

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,8 @@
2121
#include "fields2cover.h" // NOLINT
2222

2323
#include "rclcpp/rclcpp.hpp"
24-
#include "nav2_util/lifecycle_node.hpp"
25-
#include "nav2_util/node_utils.hpp"
24+
#include "nav2_ros_common/lifecycle_node.hpp"
25+
#include "nav2_ros_common/node_utils.hpp"
2626
#include "opennav_coverage/utils.hpp"
2727
#include "opennav_coverage/types.hpp"
2828

@@ -42,19 +42,19 @@ class RobotParams
4242
template<typename NodeT>
4343
explicit RobotParams(const NodeT & node)
4444
{
45-
nav2_util::declare_parameter_if_not_declared(
45+
nav2::declare_parameter_if_not_declared(
4646
node, "robot_width", rclcpp::ParameterValue(2.1));
4747
robot_.robot_width = node->get_parameter("robot_width").as_double();
4848

49-
nav2_util::declare_parameter_if_not_declared(
49+
nav2::declare_parameter_if_not_declared(
5050
node, "operation_width", rclcpp::ParameterValue(2.5));
5151
robot_.op_width = node->get_parameter("operation_width").as_double();
5252

53-
nav2_util::declare_parameter_if_not_declared(
53+
nav2::declare_parameter_if_not_declared(
5454
node, "min_turning_radius", rclcpp::ParameterValue(0.4));
5555
robot_.setMinRadius(node->get_parameter("min_turning_radius").as_double());
5656

57-
nav2_util::declare_parameter_if_not_declared(
57+
nav2::declare_parameter_if_not_declared(
5858
node, "linear_curv_change", rclcpp::ParameterValue(2.0));
5959
robot_.linear_curv_change = node->get_parameter("linear_curv_change").as_double();
6060
}

opennav_coverage/include/opennav_coverage/route_generator.hpp

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -21,8 +21,8 @@
2121
#include "fields2cover.h" // NOLINT
2222

2323
#include "rclcpp/rclcpp.hpp"
24-
#include "nav2_util/lifecycle_node.hpp"
25-
#include "nav2_util/node_utils.hpp"
24+
#include "nav2_ros_common/lifecycle_node.hpp"
25+
#include "nav2_ros_common/node_utils.hpp"
2626
#include "opennav_coverage_msgs/msg/route_mode.hpp"
2727
#include "opennav_coverage/utils.hpp"
2828
#include "opennav_coverage/types.hpp"
@@ -43,17 +43,17 @@ class RouteGenerator
4343
template<typename NodeT>
4444
explicit RouteGenerator(const NodeT & node)
4545
{
46-
nav2_util::declare_parameter_if_not_declared(
46+
nav2::declare_parameter_if_not_declared(
4747
node, "default_route_type", rclcpp::ParameterValue("BOUSTROPHEDON"));
4848
std::string type_str = node->get_parameter("default_route_type").as_string();
4949
default_type_ = toType(type_str);
5050
default_generator_ = createGenerator(default_type_);
5151

52-
nav2_util::declare_parameter_if_not_declared(
52+
nav2::declare_parameter_if_not_declared(
5353
node, "default_spiral_n", rclcpp::ParameterValue(4));
5454
default_spiral_n_ = node->get_parameter("default_spiral_n").as_int();
5555

56-
nav2_util::declare_parameter_if_not_declared(
56+
nav2::declare_parameter_if_not_declared(
5757
node, "default_custom_order", rclcpp::PARAMETER_INTEGER_ARRAY);
5858
try {
5959
// Get the custom order and cast to size_t

opennav_coverage/include/opennav_coverage/swath_generator.hpp

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -22,8 +22,8 @@
2222
#include "fields2cover.h" // NOLINT
2323

2424
#include "rclcpp/rclcpp.hpp"
25-
#include "nav2_util/lifecycle_node.hpp"
26-
#include "nav2_util/node_utils.hpp"
25+
#include "nav2_ros_common/lifecycle_node.hpp"
26+
#include "nav2_ros_common/node_utils.hpp"
2727
#include "opennav_coverage_msgs/msg/swath_mode.hpp"
2828
#include "opennav_coverage/utils.hpp"
2929
#include "opennav_coverage/types.hpp"
@@ -48,25 +48,25 @@ class SwathGenerator
4848
logger_ = node->get_logger();
4949
robot_params_ = robot_params;
5050

51-
nav2_util::declare_parameter_if_not_declared(
51+
nav2::declare_parameter_if_not_declared(
5252
node, "default_swath_type", rclcpp::ParameterValue("LENGTH"));
5353
std::string type_str = node->get_parameter("default_swath_type").as_string();
5454
default_type_ = toType(type_str);
5555

56-
nav2_util::declare_parameter_if_not_declared(
56+
nav2::declare_parameter_if_not_declared(
5757
node, "default_swath_angle_type", rclcpp::ParameterValue("BRUTE_FORCE"));
5858
std::string angle_str = node->get_parameter("default_swath_angle_type").as_string();
5959
default_angle_type_ = toAngleType(angle_str);
6060

61-
nav2_util::declare_parameter_if_not_declared(
61+
nav2::declare_parameter_if_not_declared(
6262
node, "default_swath_angle", rclcpp::ParameterValue(0.0));
6363
default_swath_angle_ = node->get_parameter("default_swath_angle").as_double();
6464

65-
nav2_util::declare_parameter_if_not_declared(
65+
nav2::declare_parameter_if_not_declared(
6666
node, "default_step_angle", rclcpp::ParameterValue(1.7453e-2));
6767
default_step_angle_ = node->get_parameter("default_step_angle").as_double();
6868

69-
nav2_util::declare_parameter_if_not_declared(
69+
nav2::declare_parameter_if_not_declared(
7070
node, "default_allow_overlap", rclcpp::ParameterValue(false));
7171
default_allow_overlap_ = node->get_parameter("default_allow_overlap").as_bool();
7272

opennav_coverage/include/opennav_coverage/utils.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,7 +24,7 @@
2424
#include "fields2cover.h" // NOLINT
2525
#include "rclcpp/rclcpp.hpp"
2626
#include "opennav_coverage/types.hpp"
27-
#include "nav2_util/node_utils.hpp"
27+
#include "nav2_ros_common/node_utils.hpp"
2828
#include "nav2_util/geometry_utils.hpp"
2929
#include "geometry_msgs/msg/point32.hpp"
3030

0 commit comments

Comments
 (0)