Skip to content

Commit 91dd205

Browse files
Mergify/bp/humble/pr 3419 (#3458)
* resolve merge conflicts for humble backport * auto-format using clang-format
1 parent b62c46d commit 91dd205

File tree

2 files changed

+3
-31
lines changed

2 files changed

+3
-31
lines changed

moveit_plugins/moveit_ros_control_interface/README.md

-5
Original file line numberDiff line numberDiff line change
@@ -22,14 +22,9 @@ In your MoveIt launch file (e.g. `ROBOT_moveit_config/launch/ROBOT_moveit_contro
2222
<param name="moveit_controller_manager" value="moveit_ros_control_interface::Ros2ControlManager" />
2323
```
2424

25-
<<<<<<< HEAD
26-
And make sure to set the `ros_control_namespace` parameter to the namespace (without the /controller_manager/ part) of the ros_control-based node you like to interface.
27-
If you are using the `moveit_setup_assistent` you can add it to `ROBOT_moveit_config/config/moveit_controllers.yaml`, e.g.:
28-
=======
2925
Make sure to set the `ros_control_namespace` parameter to the namespace (without the /controller_manager/ part) of the ros_control-based node you like to interface.
3026
Also, the timeout in seconds for the service call to the controller can be changed from the default value, by setting the `controller_service_call_timeout` parameter.
3127
If you are using `moveit_setup_assistant`, you can add it to `ROBOT_moveit_config/config/moveit_controllers.yaml`, e.g.:
32-
>>>>>>> 64e934ff4 (ROS Parameter for service call timeout for ros_control controllers (#3419))
3328
```
3429
ros_control_namespace: /ROS_CONTROL_NODE
3530
controller_service_call_timeout: 5.0

moveit_plugins/moveit_ros_control_interface/src/controller_manager_plugin.cpp

+3-26
Original file line numberDiff line numberDiff line change
@@ -59,19 +59,8 @@ static const rclcpp::Duration CONTROLLER_INFORMATION_VALIDITY_AGE = rclcpp::Dura
5959

6060
namespace moveit_ros_control_interface
6161
{
62-
<<<<<<< HEAD
63-
=======
6462
static constexpr double DEFAULT_SERVICE_CALL_TIMEOUT = 3.0;
6563

66-
namespace
67-
{
68-
rclcpp::Logger getLogger()
69-
{
70-
return moveit::getLogger("moveit.plugins.ros_control_interface");
71-
}
72-
} // namespace
73-
74-
>>>>>>> 64e934ff4 (ROS Parameter for service call timeout for ros_control controllers (#3419))
7564
/**
7665
* \brief Get joint name from resource name reported by ros2_control, since claimed_interfaces return by ros2_control
7766
* will have the interface name as suffix joint_name/INTERFACE_TYPE
@@ -195,15 +184,9 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
195184
auto result_future = list_controllers_service_->async_send_request(request);
196185
if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
197186
{
198-
<<<<<<< HEAD
199187
RCLCPP_WARN_STREAM(LOGGER, "Failed to read controllers from " << list_controllers_service_->get_service_name()
200-
<< " within " << SERVICE_CALL_TIMEOUT
188+
<< " within " << service_call_timeout_.count()
201189
<< " seconds");
202-
=======
203-
RCLCPP_WARN_STREAM(getLogger(), "Failed to read controllers from "
204-
<< list_controllers_service_->get_service_name() << " within "
205-
<< service_call_timeout_.count() << " seconds");
206-
>>>>>>> 64e934ff4 (ROS Parameter for service call timeout for ros_control controllers (#3419))
207190
return;
208191
}
209192

@@ -337,7 +320,7 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
337320
}
338321
service_call_timeout_ = std::chrono::duration<double>(timeout_seconds);
339322

340-
RCLCPP_INFO_STREAM(getLogger(), "Using service call timeout " << service_call_timeout_.count() << " seconds");
323+
RCLCPP_INFO_STREAM(LOGGER, "Using service call timeout " << service_call_timeout_.count() << " seconds");
341324

342325
list_controllers_service_ = node_->create_client<controller_manager_msgs::srv::ListControllers>(
343326
getAbsName("controller_manager/list_controllers"));
@@ -557,15 +540,9 @@ class Ros2ControlManager : public moveit_controller_manager::MoveItControllerMan
557540
auto result_future = switch_controller_service_->async_send_request(request);
558541
if (result_future.wait_for(service_call_timeout_) == std::future_status::timeout)
559542
{
560-
<<<<<<< HEAD
561543
RCLCPP_ERROR_STREAM(LOGGER, "Couldn't switch controllers at " << switch_controller_service_->get_service_name()
562-
<< " within " << SERVICE_CALL_TIMEOUT
544+
<< " within " << service_call_timeout_.count()
563545
<< " seconds");
564-
=======
565-
RCLCPP_ERROR_STREAM(getLogger(), "Couldn't switch controllers at "
566-
<< switch_controller_service_->get_service_name() << " within "
567-
<< service_call_timeout_.count() << " seconds");
568-
>>>>>>> 64e934ff4 (ROS Parameter for service call timeout for ros_control controllers (#3419))
569546
return false;
570547
}
571548
discover(true);

0 commit comments

Comments
 (0)