Skip to content

Commit

Permalink
change namespace for service tools
Browse files Browse the repository at this point in the history
  • Loading branch information
Svastits committed Jan 27, 2023
1 parent 26b87ab commit 859cf2b
Show file tree
Hide file tree
Showing 4 changed files with 24 additions and 24 deletions.
14 changes: 7 additions & 7 deletions kuka_rox_hardware_interface/src/robot_manager_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &)
hw_request->name = "iisy_hardware";
hw_request->target_state.label = "inactive";
auto hw_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
change_hardware_state_client_, hw_request, 0, 2000
);
if (!hw_response || !hw_response->ok) {
Expand All @@ -73,7 +73,7 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &)
hw_request->name = "iisy_hardware";
hw_request->target_state.label = "inactive";
auto hw_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
change_hardware_state_client_, hw_request, 0, 2000
);
if (!hw_response || !hw_response->ok) {
Expand Down Expand Up @@ -120,7 +120,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &)
hw_request->name = "iisy_hardware";
hw_request->target_state.label = "active";
auto hw_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
change_hardware_state_client_, hw_request, 0, 2000
);
if (!hw_response || !hw_response->ok) {
Expand All @@ -137,7 +137,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &)
controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
controller_request->activate_controllers = std::vector<std::string>{"joint_state_broadcaster"};
auto controller_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
change_controller_state_client_, controller_request, 0, 2000
);
if (!controller_response || !controller_response->ok) {
Expand All @@ -162,7 +162,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &)
controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
controller_request->activate_controllers = controller_names_;
controller_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
change_controller_state_client_, controller_request, 0, 2000
);
if (!controller_response || !controller_response->ok) {
Expand All @@ -185,7 +185,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &)
hw_request->name = "iisy_hardware";
hw_request->target_state.label = "inactive";
auto hw_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
change_hardware_state_client_, hw_request, 0, 2000
);
if (!hw_response || !hw_response->ok) {
Expand All @@ -204,7 +204,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &)
controller_manager_msgs::srv::SwitchController::Request::BEST_EFFORT;
controller_request->deactivate_controllers = controller_names_;
auto controller_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
change_controller_state_client_, controller_request, 0, 2000
);
if (!controller_response || !controller_response->ok) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,7 @@ bool ConfigurationManager::onControllerNameChangeRequest(
{
auto request = std::make_shared<controller_manager_msgs::srv::ListControllers::Request>();
auto response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::ListControllers::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::ListControllers::Response>(
get_controllers_client_, request, 0, 1000);

if (!response) {
Expand Down Expand Up @@ -264,7 +264,7 @@ bool ConfigurationManager::setReceiveMultiplier(int receive_multiplier) const
// Set receive multiplier of hardware interface through controller manager service
auto request = std::make_shared<kuka_driver_interfaces::srv::SetInt::Request>();
request->data = receive_multiplier;
auto response = kuka_sunrise::sendRequest<kuka_driver_interfaces::srv::SetInt::Response>(
auto response = kroshu_ros2_core::sendRequest<kuka_driver_interfaces::srv::SetInt::Response>(
receive_multiplier_client_, request, 0, 1000);

if (!response || !response->success) {
Expand Down
10 changes: 5 additions & 5 deletions kuka_sunrise_driver/src/kuka_sunrise/robot_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,11 +115,11 @@ bool RobotManager::setJointImpedanceControlMode(
}
for (double js : joint_stiffness) {
printf("js = %lf\n", js);
msg_size += serializeNext(js, serialized);
msg_size += kroshu_ros2_core::serializeNext(js, serialized);
}
for (double jd : joint_damping) {
printf("jd = %lf\n", jd);
msg_size += serializeNext(jd, serialized);
msg_size += kroshu_ros2_core::serializeNext(jd, serialized);
}
return sendCommandAndWait(SET_CONTROL_MODE, serialized);
}
Expand All @@ -139,9 +139,9 @@ bool RobotManager::setFRIConfig(int remote_port, int send_period_ms, int receive
serialized.emplace_back(byte);
msg_size++;
}
msg_size += serializeNext(remote_port, serialized);
msg_size += serializeNext(send_period_ms, serialized);
msg_size += serializeNext(receive_multiplier, serialized);
msg_size += kroshu_ros2_core::serializeNext(remote_port, serialized);
msg_size += kroshu_ros2_core::serializeNext(send_period_ms, serialized);
msg_size += kroshu_ros2_core::serializeNext(receive_multiplier, serialized);
return sendCommandAndWait(SET_FRI_CONFIG, serialized);
}

Expand Down
20 changes: 10 additions & 10 deletions kuka_sunrise_driver/src/kuka_sunrise/robot_manager_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &)
hw_request->name = "iiwa_hardware";
hw_request->target_state.label = "inactive";
auto hw_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
change_hardware_state_client_, hw_request, 0, 2000);
if (!hw_response || !hw_response->ok) {
RCLCPP_ERROR(get_logger(), "Could not configure hardware interface");
Expand All @@ -93,7 +93,7 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &)
controller_request->activate_controllers =
std::vector<std::string>{"timing_controller", "robot_state_broadcaster"};
auto controller_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
change_controller_state_client_, controller_request, 0, 3000);
if (!controller_response || !controller_response->ok) {
RCLCPP_ERROR(get_logger(), "Could not start controllers");
Expand All @@ -115,7 +115,7 @@ RobotManagerNode::on_configure(const rclcpp_lifecycle::State &)
if (result == SUCCESS) {
auto trigger_request =
std::make_shared<std_srvs::srv::Trigger::Request>();
auto response = kuka_sunrise::sendRequest<std_srvs::srv::Trigger::Response>(
auto response = kroshu_ros2_core::sendRequest<std_srvs::srv::Trigger::Response>(
set_parameter_client_, trigger_request, 0, 1000);

if (!response || !response->success) {
Expand Down Expand Up @@ -151,7 +151,7 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &)
controller_request->deactivate_controllers =
std::vector<std::string>{"timing_controller", "robot_state_broadcaster"};
auto controller_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
change_controller_state_client_, controller_request, 0, 2000);
if (!controller_response || !controller_response->ok) {
RCLCPP_ERROR(get_logger(), "Could not stop controllers");
Expand All @@ -165,7 +165,7 @@ RobotManagerNode::on_cleanup(const rclcpp_lifecycle::State &)
hw_request->name = "iiwa_hardware";
hw_request->target_state.label = "unconfigured";
auto hw_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
change_hardware_state_client_, hw_request, 0, 2000);
if (!hw_response || !hw_response->ok) {
RCLCPP_ERROR(get_logger(), "Could not cleanup hardware interface");
Expand Down Expand Up @@ -233,7 +233,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &)
hw_request->name = "iiwa_hardware";
hw_request->target_state.label = "active";
auto hw_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
change_hardware_state_client_, hw_request, 0, 2000);
if (!hw_response || !hw_response->ok) {
RCLCPP_ERROR(get_logger(), "Could not activate hardware interface");
Expand All @@ -258,7 +258,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &)
controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
controller_request->activate_controllers = std::vector<std::string>{"joint_state_broadcaster"};
auto controller_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
change_controller_state_client_, controller_request, 0, 2000);
if (!controller_response || !controller_response->ok) {
RCLCPP_ERROR(get_logger(), "Could not start joint state broadcaster");
Expand All @@ -274,7 +274,7 @@ RobotManagerNode::on_activate(const rclcpp_lifecycle::State &)
controller_request->strictness = controller_manager_msgs::srv::SwitchController::Request::STRICT;
controller_request->activate_controllers = std::vector<std::string>{controller_name_};
controller_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
change_controller_state_client_, controller_request, 0, 2000);
if (!controller_response || !controller_response->ok) {
RCLCPP_ERROR(get_logger(), "Could not activate controller");
Expand Down Expand Up @@ -317,7 +317,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &)
hw_request->name = "iiwa_hardware";
hw_request->target_state.label = "inactive";
auto hw_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SetHardwareComponentState::Response>(
change_hardware_state_client_, hw_request, 0, 2000);
if (!hw_response || !hw_response->ok) {
RCLCPP_ERROR(get_logger(), "Could not deactivate hardware interface");
Expand All @@ -334,7 +334,7 @@ RobotManagerNode::on_deactivate(const rclcpp_lifecycle::State &)
controller_request->deactivate_controllers =
std::vector<std::string>{controller_name_, "joint_state_broadcaster"};
auto controller_response =
kuka_sunrise::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
kroshu_ros2_core::sendRequest<controller_manager_msgs::srv::SwitchController::Response>(
change_controller_state_client_, controller_request, 0, 2000);
if (!controller_response || !controller_response->ok) {
RCLCPP_ERROR(get_logger(), "Could not stop controllers");
Expand Down

0 comments on commit 859cf2b

Please sign in to comment.