mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-12 19:10:47 +02:00
implemented setting of speed_slider via ROS topic
This commit is contained in:
@@ -216,6 +216,8 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
|
||||
}
|
||||
tool_data_pub_.reset(new realtime_tools::RealtimePublisher<ur_msgs::ToolDataMsg>(robot_hw_nh, "tool_data", 1));
|
||||
|
||||
speed_slider_sub_ = robot_hw_nh.subscribe("set_speed_slider", 10, &HardwareInterface::speedScalingCallback, this);
|
||||
|
||||
deactivate_srv_ = robot_hw_nh.advertiseService("hand_back_control", &HardwareInterface::stopControl, this);
|
||||
|
||||
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_rtde_driver hardware_interface");
|
||||
@@ -533,4 +535,9 @@ bool HardwareInterface::stopControl(std_srvs::TriggerRequest& req, std_srvs::Tri
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void HardwareInterface::speedScalingCallback(const std_msgs::Float64::ConstPtr& msg)
|
||||
{
|
||||
ur_driver_->getRTDEWriter().sendSpeedSlider(msg->data);
|
||||
}
|
||||
} // namespace ur_driver
|
||||
|
||||
Reference in New Issue
Block a user