Skip to content

Commit

Permalink
Changes for humble
Browse files Browse the repository at this point in the history
Signed-off-by: Alberto Tudela <ajtudela@gmail.com>
  • Loading branch information
ajtudela committed Feb 12, 2024
1 parent 70dc1f9 commit d33298e
Show file tree
Hide file tree
Showing 7 changed files with 26 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -135,7 +135,7 @@ bool BtActionServer<ActionT>::on_configure()
node, "robot_base_frame", rclcpp::ParameterValue(std::string("base_link")));
nav2_util::declare_parameter_if_not_declared(
node, "transform_tolerance", rclcpp::ParameterValue(0.1));
rclcpp::copy_all_parameter_values(node, client_node_);
nav2_util::copy_all_parameters(node, client_node_);

// set the timeout in seconds for the action server to discard goal handles if not finished
double action_server_result_timeout;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,7 @@ class BtServiceNode : public BT::ActionNodeBase
getInput("service_name", service_name_);
service_client_ = node_->create_client<ServiceT>(
service_name_,
rclcpp::SystemDefaultsQoS(),
rclcpp::ServicesQoS().get_rmw_qos_profile(),
callback_group_);

// Make a request for the service without parameter
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/src/collision_detector_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ CollisionDetector::on_activate(const rclcpp_lifecycle::State & /*state*/)
}

// Creating timer
timer_ = this->create_timer(
timer_ = this->create_wall_timer(
std::chrono::duration<double>{1.0 / frequency_},
std::bind(&CollisionDetector::process, this));

Expand Down
4 changes: 2 additions & 2 deletions nav2_lifecycle_manager/src/lifecycle_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,13 +64,13 @@ LifecycleManager::LifecycleManager(const rclcpp::NodeOptions & options)
manager_srv_ = create_service<ManageLifecycleNodes>(
get_name() + std::string("/manage_nodes"),
std::bind(&LifecycleManager::managerCallback, this, _1, _2, _3),
rclcpp::SystemDefaultsQoS(),
rclcpp::ServicesQoS().get_rmw_qos_profile(),
callback_group_);

is_active_srv_ = create_service<std_srvs::srv::Trigger>(
get_name() + std::string("/is_active"),
std::bind(&LifecycleManager::isActiveCallback, this, _1, _2, _3),
rclcpp::SystemDefaultsQoS(),
rclcpp::ServicesQoS().get_rmw_qos_profile(),
callback_group_);

transition_state_map_[Transition::TRANSITION_CONFIGURE] = State::PRIMARY_STATE_INACTIVE;
Expand Down
19 changes: 19 additions & 0 deletions nav2_util/include/nav2_util/node_utils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -160,6 +160,25 @@ std::string get_plugin_type_param(
*/
void setSoftRealTimePriority();

/**
* @brief A method to copy all parameters from one node (parent) to another (child).
* May throw parameter exceptions in error conditions
* @param parent Node to copy parameters from
* @param child Node to copy parameters to
*/
template<typename NodeT1, typename NodeT2>
void copy_all_parameters(const NodeT1 & parent, const NodeT2 & child)
{
using Parameters = std::vector<rclcpp::Parameter>;
std::vector<std::string> param_names = parent->list_parameters({}, 0).names;
Parameters params = parent->get_parameters(param_names);
for (Parameters::const_iterator iter = params.begin(); iter != params.end(); ++iter) {
if (!child->has_parameter(iter->get_name())) {
child->declare_parameter(iter->get_name(), iter->get_parameter_value());
}
}
}

} // namespace nav2_util

#endif // NAV2_UTIL__NODE_UTILS_HPP_
2 changes: 1 addition & 1 deletion nav2_util/include/nav2_util/service_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ class ServiceClient
callback_group_executor_.add_callback_group(callback_group_, node_->get_node_base_interface());
client_ = node_->template create_client<ServiceT>(
service_name,
rclcpp::SystemDefaultsQoS(),
rclcpp::ServicesQoS().get_rmw_qos_profile(),
callback_group_);
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@
#include "nav2_core/waypoint_task_executor.hpp"
#include "opencv4/opencv2/core.hpp"
#include "opencv4/opencv2/opencv.hpp"
#include "cv_bridge/cv_bridge.hpp"
#include "cv_bridge/cv_bridge.h"
#include "image_transport/image_transport.hpp"


Expand Down

0 comments on commit d33298e

Please sign in to comment.