Skip to content

Commit 5e4388d

Browse files
committed
Change default logging level
1 parent 8a8e266 commit 5e4388d

2 files changed

Lines changed: 51 additions & 3 deletions

File tree

.github/workflows/jazzy.yaml

Lines changed: 49 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,49 @@
1+
2+
name: jazzy
3+
4+
on:
5+
pull_request:
6+
branches:
7+
- jazzy
8+
push:
9+
branches:
10+
- jazzy
11+
schedule:
12+
- cron: '0 0 * * 6'
13+
jobs:
14+
build-and-test:
15+
runs-on: ${{ matrix.os }}
16+
strategy:
17+
matrix:
18+
os: [ubuntu-24.04]
19+
fail-fast: false
20+
steps:
21+
- uses: actions/checkout@v4
22+
with:
23+
ref: jazzy
24+
- name: Setup ROS 2
25+
uses: ros-tooling/setup-ros@0.7.15
26+
with:
27+
required-ros-distributions: jazzy
28+
- name: build and test
29+
uses: ros-tooling/action-ros-ci@0.4.5
30+
with:
31+
package-name: easynav_gridmap_maps_manager easynav_gridmap_astar_planner easynav_gridmap_rrtstar_planner
32+
target-ros2-distro: jazzy
33+
vcs-repo-file-url: ${GITHUB_WORKSPACE}/.github/thirdparty.repos
34+
colcon-defaults: |
35+
{
36+
"test": {
37+
"parallel-workers" : 1
38+
}
39+
}
40+
colcon-mixin-name: coverage-gcc
41+
colcon-mixin-repository: https://raw.githubusercontent.com/colcon/colcon-mixin-repository/master/index.yaml
42+
- name: Codecov
43+
uses: codecov/codecov-action@v5.4.0
44+
with:
45+
files: ros_ws/lcov/total_coverage.info
46+
flags: unittests
47+
name: codecov-umbrella
48+
# yml: ./codecov.yml
49+
fail_ci_if_error: false

easynav_gridmap_rrtstar_planner/src/easynav_gridmap_rrtstar_planner/GridMapRRTStarPlanner.cpp

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ std::expected<void, std::string> GridMapRRTStarPlanner::on_initialize()
9191
node->declare_parameter<double>(plugin_name + ".spacing", 0.2);
9292
node->declare_parameter<double>(plugin_name + ".max_lateral_deviation", 0.5);
9393
node->declare_parameter<int>(plugin_name + ".final_poses_with_goal_orientation", 2);
94-
94+
9595
node->get_parameter(plugin_name + ".max_allowed_slope_deg", max_allowed_slope_deg_);
9696
node->get_parameter(plugin_name + ".max_iters", max_iters_);
9797
node->get_parameter(plugin_name + ".step_size", step_size_);
@@ -109,7 +109,7 @@ std::expected<void, std::string> GridMapRRTStarPlanner::on_initialize()
109109
path_pub_ = node->create_publisher<nav_msgs::msg::Path>("planner/path", 10);
110110
marker_pub_ = node->create_publisher<visualization_msgs::msg::MarkerArray>("planner/marker", 10);
111111

112-
node->get_logger().set_level(rclcpp::Logger::Level::Debug);
112+
node->get_logger().set_level(rclcpp::Logger::Level::Warn);
113113

114114
last_goal_pose_.position.x = 0.0;
115115
last_goal_pose_.position.y = 0.0;
@@ -692,7 +692,6 @@ bool GridMapRRTStarPlanner::check_goal_changed(const geometry_msgs::msg::Pose &
692692
return goal_changed;
693693
}
694694

695-
// Replace entire update() function:
696695
void GridMapRRTStarPlanner::update(NavState & nav_state)
697696
{
698697
// initial validations

0 commit comments

Comments
 (0)