Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -401,7 +401,7 @@ AmclNode::checkLaserReceived()
RCLCPP_WARN(
get_logger(), "Laser scan has not been received"
" (and thus no pose updates have been published)."
" Verify that data is being published on the %s topic.", scan_topic_);
" Verify that data is being published on the %s topic.", scan_topic_.c_str());
return;
}

Expand All @@ -410,7 +410,7 @@ AmclNode::checkLaserReceived()
RCLCPP_WARN(
get_logger(), "No laser scan received (and thus no pose updates have been published) for %f"
" seconds. Verify that data is being published on the %s topic.",
d.nanoseconds() * 1e-9, scan_topic_);
d.nanoseconds() * 1e-9, scan_topic_.c_str());
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,11 @@ class BtActionNode : public BT::ActionNodeBase
const BT::NodeConfiguration & conf)
: BT::ActionNodeBase(xml_tag_name, conf), action_name_(action_name)
{
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>("node");

// Get the required items from the blackboard
server_timeout_ =
config().blackboard->get<std::chrono::milliseconds>("server_timeout");
config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);

// Initialize the input and output messages
Expand Down Expand Up @@ -245,9 +245,9 @@ class BtActionNode : public BT::ActionNodeBase
void increment_recovery_count()
{
int recovery_count = 0;
config().blackboard->get<int>("number_recoveries", recovery_count); // NOLINT
config().blackboard->template get<int>("number_recoveries", recovery_count); // NOLINT
recovery_count += 1;
config().blackboard->set<int>("number_recoveries", recovery_count); // NOLINT
config().blackboard->template set<int>("number_recoveries", recovery_count); // NOLINT
}

std::string action_name_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,11 +35,11 @@ class BtServiceNode : public BT::SyncActionNode
const BT::NodeConfiguration & conf)
: BT::SyncActionNode(service_node_name, conf), service_node_name_(service_node_name)
{
node_ = config().blackboard->get<rclcpp::Node::SharedPtr>("node");
node_ = config().blackboard->template get<rclcpp::Node::SharedPtr>("node");

// Get the required items from the blackboard
server_timeout_ =
config().blackboard->get<std::chrono::milliseconds>("server_timeout");
config().blackboard->template get<std::chrono::milliseconds>("server_timeout");
getInput<std::chrono::milliseconds>("server_timeout", server_timeout_);

// Now that we have node_ to use, create the service client for this BT service
Expand Down Expand Up @@ -126,9 +126,9 @@ class BtServiceNode : public BT::SyncActionNode
void increment_recovery_count()
{
int recovery_count = 0;
config().blackboard->get<int>("number_recoveries", recovery_count); // NOLINT
config().blackboard->template get<int>("number_recoveries", recovery_count); // NOLINT
recovery_count += 1;
config().blackboard->set<int>("number_recoveries", recovery_count); // NOLINT
config().blackboard->template set<int>("number_recoveries", recovery_count); // NOLINT
}

std::string service_name_, service_node_name_;
Expand Down
5 changes: 0 additions & 5 deletions nav2_bt_navigator/src/ros_topic_logger.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,7 @@ void RosTopicLogger::callback(

// BT timestamps are a duration since the epoch. Need to convert to a time_point
// before converting to a msg.
#ifndef _WIN32
event.timestamp =
tf2_ros::toMsg(std::chrono::time_point<std::chrono::high_resolution_clock>(timestamp));
#else
event.timestamp = tf2_ros::toMsg(tf2::TimePoint(timestamp));
#endif
event.node_name = node.name();
event.previous_status = toStr(prev_status, false);
event.current_status = toStr(status, false);
Expand Down
5 changes: 5 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/observation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,11 @@ class Observation
delete cloud_;
}

/**
* @brief Explicitly define copy assignment operator for Observation as it has a user-declared destructor
*/
Observation & operator=(const Observation &) = default;

/**
* @brief Creates an observation from an origin point and a point cloud
* @param origin The origin point of the observation
Expand Down
2 changes: 1 addition & 1 deletion nav2_recoveries/include/nav2_recoveries/recovery.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ class Recovery : public nav2_core::Recovery

collision_checker_ = collision_checker;

vel_pub_ = node_->create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 1);
vel_pub_ = node_->template create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 1);

onConfigure();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -229,7 +229,7 @@ geometry_msgs::msg::TwistStamped RegulatedPurePursuitController::computeVelocity
// Find look ahead distance and point on path and publish
const double lookahead_dist = getLookAheadDistance(speed);
auto carrot_pose = getLookAheadPoint(lookahead_dist, transformed_plan);
carrot_pub_->publish(std::move(createCarrotMsg(carrot_pose)));
carrot_pub_->publish(createCarrotMsg(carrot_pose));

double linear_vel, angular_vel;

Expand Down
1 change: 1 addition & 0 deletions nav2_util/src/dump_params.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@

#include <iomanip>
#include <iostream>
#include <libgen.h>
#include <memory>
#include <sstream>
#include <string>
Expand Down
3 changes: 1 addition & 2 deletions nav2_waypoint_follower/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,6 @@
<maintainer email="[email protected]">Steve Macenski</maintainer>
<license>Apache-2.0</license>

<depend>tf2_ros</depend>

<buildtool_depend>ament_cmake</buildtool_depend>
<depend>nav2_common</depend>
<depend>rclcpp</depend>
Expand All @@ -17,6 +15,7 @@
<depend>nav_msgs</depend>
<depend>nav2_msgs</depend>
<depend>nav2_util</depend>
<depend>tf2_ros</depend>

<test_depend>ament_lint_common</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
2 changes: 1 addition & 1 deletion smac_planner/src/a_star.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -352,7 +352,7 @@ AStarAlgorithm<NodeSE2>::NodePtr AStarAlgorithm<NodeSE2>::getAnalyticPath(
float d = node->motion_table.state_space->distance(from(), to());
NodePtr prev(node);
// A move of sqrt(2) is guaranteed to be in a new cell
constexpr float sqrt_2 = std::sqrt(2.);
static const float sqrt_2 = std::sqrt(2.);
unsigned int num_intervals = std::floor(d / sqrt_2);

using PossibleNode = std::pair<NodePtr, Coordinates>;
Expand Down