hw_interface.cpp
Go to the documentation of this file.
1 // -- BEGIN LICENSE BLOCK ----------------------------------------------
2 // Copyright 2020 FZI Forschungszentrum Informatik
3 // Created on behalf of Universal Robots A/S
4 //
5 // Licensed under the Apache License, Version 2.0 (the "License");
6 // you may not use this file except in compliance with the License.
7 // You may obtain a copy of the License at
8 //
9 // http://www.apache.org/licenses/LICENSE-2.0
10 //
11 // Unless required by applicable law or agreed to in writing, software
12 // distributed under the License is distributed on an "AS IS" BASIS,
13 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 // See the License for the specific language governing permissions and
15 // limitations under the License.
16 // -- END LICENSE BLOCK ------------------------------------------------
17 
18 //-----------------------------------------------------------------------------
25 //-----------------------------------------------------------------------------
26 
27 #include "hw_interface.h"
32 #include "control_msgs/FollowJointTrajectoryAction.h"
33 #include "control_msgs/FollowJointTrajectoryActionGoal.h"
34 #include "control_msgs/FollowJointTrajectoryFeedback.h"
35 #include "control_msgs/FollowJointTrajectoryGoal.h"
36 #include "control_msgs/FollowJointTrajectoryResult.h"
38 #include "ros/duration.h"
39 #include <functional>
40 
41 namespace examples
42 {
44 {
45  // Get names of controllable joints from the parameter server
46  ros::NodeHandle nh;
47  if (!nh.getParam("joints", joint_names_))
48  {
49  ROS_ERROR_STREAM("Failed to load " << nh.getNamespace() + "/joints"
50  << " from parameter server");
51  throw std::logic_error("Failed to initialize ros control.");
52  }
53 
54  // Current UR driver convention
55  ref_frame_id_ = "base";
56  frame_id_ = "tool0_controller";
57 
58  // Connect dynamic reconfigure and overwrite the default values with values
59  // on the parameter server. This is done automatically if parameters with
60  // the according names exist.
62  std::bind(&HWInterface::dynamicReconfigureCallback, this, std::placeholders::_1, std::placeholders::_2);
63 
64  reconfig_server_ = std::make_shared<dynamic_reconfigure::Server<SpeedScalingConfig> >(nh);
65  reconfig_server_->setCallback(callback_type_);
66 
67  const int nr_joints = joint_names_.size();
68  cmd_.resize(nr_joints);
69  pos_.resize(nr_joints);
70  vel_.resize(nr_joints);
71  eff_.resize(nr_joints);
72 
73  // Initialize and register joint state handles
74  for (int i = 0; i < nr_joints; ++i)
75  {
77 
79  }
81 
82  // Initialize and register a Cartesian state handle
86  cart_state_interface_.registerHandle(cartesian_state_handle);
88 
89  // Initialize and register a Cartesian pose command handle
92  pose_cmd_interface_.registerHandle(pose_cmd_handle);
94 
95  // Initialize and register joint position command handles.
96  for (int i = 0; i < nr_joints; ++i)
97  {
98  joint_handles_.push_back(
100 
102  }
104 
105  // Initialize and prepare joint trajectory interface for PassThroughControllers
107  std::bind(&HWInterface::startJointInterpolation, this, std::placeholders::_1));
110 
111  // Initialize and prepare Cartesian trajectory interface for PassThroughControllers
113  std::bind(&HWInterface::startCartesianInterpolation, this, std::placeholders::_1));
116 
117  // Initialize and register speed scaling.
118  // Note: The handle's name is a convention.
119  // ROS-controllers will use this name when calling getHandle().
120  speedsc_interface_.registerHandle(scaled_controllers::SpeedScalingHandle("speed_scaling_factor", &speed_scaling_));
122 
123  // Robot dummy communication
125  std::make_unique<actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> >("joint_trajectory_"
126  "controller/"
127  "follow_joint_"
128  "trajectory",
129  true);
130 
132  std::make_unique<actionlib::SimpleActionClient<cartesian_control_msgs::FollowCartesianTrajectoryAction> >("cartes"
133  "ian_"
134  "trajec"
135  "tory_"
136  "contro"
137  "ller/"
138  "follow"
139  "_carte"
140  "sian_"
141  "trajec"
142  "tory",
143  true);
144 
145  if (!joint_based_communication_->waitForServer(ros::Duration(10)) ||
146  !cartesian_based_communication_->waitForServer(ros::Duration(10)))
147  {
148  ROS_ERROR("Trajectory action interfaces of the robot dummy are not available.");
149  return;
150  };
151 
152  ROS_INFO("Example HW interface is ready");
153 }
154 
156 {
157 }
158 
159 void HWInterface::read(const ros::Time& time, const ros::Duration& period)
160 {
161  // Code for conventional ROS-control loop here.
162 }
163 
164 void HWInterface::write(const ros::Time& time, const ros::Duration& period)
165 {
166  // Code for conventional ROS-control loop here.
167 }
168 
170 {
171  joint_based_communication_->sendGoal(
172  trajectory, std::bind(&HWInterface::handleJointDone, this, std::placeholders::_1, std::placeholders::_2),
173  0, // no active callback
174  std::bind(&HWInterface::handleJointFeedback, this, std::placeholders::_1)); // Process feedback continuously
175 }
176 
178 {
180  trajectory, std::bind(&HWInterface::handleCartesianDone, this, std::placeholders::_1, std::placeholders::_2),
181  0, // no active callback
182  std::bind(&HWInterface::handleCartesianFeedback, this, std::placeholders::_1)); // Process feedback continuously
183 }
184 
186 {
187  joint_based_communication_->cancelGoal();
188 
189  // For your driver implementation, you might want to wait here for the robot to
190  // actually cancel the execution.
191 
193 }
194 
196 {
197  cartesian_based_communication_->cancelGoal();
198 
199  // For your driver implementation, you might want to wait here for the robot to
200  // actually cancel the execution.
201 
203 }
204 
206 {
207  // Let's hope for "thread safety" with fundamental types.
208  speed_scaling_ = config.speed_scaling;
209 }
210 
211 void HWInterface::handleJointFeedback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr& feedback)
212 {
213  jnt_traj_interface_.setFeedback(*feedback);
214 }
215 
217  const control_msgs::FollowJointTrajectoryResultConstPtr& result)
218 {
220  {
222  return;
223  }
224 
225  if (result->error_code == control_msgs::FollowJointTrajectoryResult::SUCCESSFUL)
226  {
228  return;
229  }
230 
232 }
233 
235  const cartesian_control_msgs::FollowCartesianTrajectoryFeedbackConstPtr& feedback)
236 {
238 }
239 
241  const cartesian_control_msgs::FollowCartesianTrajectoryResultConstPtr& result)
242 {
244  {
246  return;
247  }
248 
249  if (result->error_code == control_msgs::FollowJointTrajectoryResult::SUCCESSFUL)
250  {
252  return;
253  }
254 
256 }
257 
258 } // namespace examples
hardware_interface::ExecutionState::SUCCESS
@ SUCCESS
examples::HWInterface::pose_cmd_
geometry_msgs::Pose pose_cmd_
Definition: hw_interface.h:132
examples::HWInterface::pos_
std::vector< double > pos_
Definition: hw_interface.h:128
examples::HWInterface::speed_scaling_
double speed_scaling_
Definition: hw_interface.h:131
examples::HWInterface::cmd_
std::vector< double > cmd_
Definition: hw_interface.h:127
examples::HWInterface::startJointInterpolation
void startJointInterpolation(const hardware_interface::JointTrajectory &trajectory)
Dummy implementation for joint interpolation on the robot.
Definition: hw_interface.cpp:169
examples::HWInterface::ref_frame_id_
std::string ref_frame_id_
Definition: hw_interface.h:135
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros_controllers_cartesian::CartesianStateHandle
scaled_controllers::SpeedScalingHandle
examples::HWInterface::cartesian_pose_
geometry_msgs::Pose cartesian_pose_
Definition: hw_interface.h:159
hardware_interface::TrajectoryInterface::registerCancelCallback
void registerCancelCallback(std::function< void()> f)
Register a RobotHW-side callback for canceling requests.
Definition: trajectory_interface.h:126
examples::HWInterface::callback_type_
dynamic_reconfigure::Server< SpeedScalingConfig >::CallbackType callback_type_
Definition: hw_interface.h:156
HardwareResourceManager< JointStateHandle >::getHandle
JointStateHandle getHandle(const std::string &name)
examples::HWInterface::cartesian_jerk_
geometry_msgs::Accel cartesian_jerk_
Definition: hw_interface.h:162
examples::HWInterface::joint_based_communication_
std::unique_ptr< actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > > joint_based_communication_
Definition: hw_interface.h:169
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
hardware_interface::InterfaceManager::registerInterface
void registerInterface(T *iface)
examples::HWInterface::cart_state_interface_
ros_controllers_cartesian::CartesianStateInterface cart_state_interface_
Definition: hw_interface.h:118
examples::HWInterface::cartesian_twist_
geometry_msgs::Twist cartesian_twist_
Definition: hw_interface.h:160
actionlib::SimpleClientGoalState
examples::HWInterface::read
void read(const ros::Time &time, const ros::Duration &period) override
Definition: hw_interface.cpp:159
examples::HWInterface::SpeedScalingConfig
pass_through_controllers::SpeedScalingConfig SpeedScalingConfig
Definition: hw_interface.h:139
trajectory_interface.h
examples::HWInterface::cart_traj_interface_
hardware_interface::CartesianTrajectoryInterface cart_traj_interface_
Definition: hw_interface.h:123
examples::HWInterface::jnt_pos_interface_
hardware_interface::PositionJointInterface jnt_pos_interface_
Definition: hw_interface.h:121
examples::HWInterface::handleJointDone
void handleJointDone(const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result)
Definition: hw_interface.cpp:216
cartesian_command_interface.h
ros_controllers_cartesian::PoseCommandHandle
examples::HWInterface::cancelJointInterpolation
void cancelJointInterpolation()
Dummy implementation for canceling a running joint interpolation on the robot.
Definition: hw_interface.cpp:185
hardware_interface::TrajectoryInterface::setDone
void setDone(const ExecutionState &state)
RobotHW-side method to mark the execution of a trajectory done.
Definition: trajectory_interface.h:178
examples::HWInterface::jnt_traj_interface_
hardware_interface::JointTrajectoryInterface jnt_traj_interface_
Definition: hw_interface.h:122
duration.h
examples::HWInterface::vel_
std::vector< double > vel_
Definition: hw_interface.h:129
examples::HWInterface::reconfig_server_
std::shared_ptr< dynamic_reconfigure::Server< SpeedScalingConfig > > reconfig_server_
Definition: hw_interface.h:155
simple_action_client.h
hw_interface.h
hardware_interface::TrajectoryInterface::registerGoalCallback
void registerGoalCallback(std::function< void(const TrajectoryType &)> f)
Register a RobotHW-side callback for new trajectory execution.
Definition: trajectory_interface.h:116
examples::HWInterface::cancelCartesianInterpolation
void cancelCartesianInterpolation()
Dummy implementation for canceling a running Cartesian interpolation on the robot.
Definition: hw_interface.cpp:195
examples::HWInterface::write
void write(const ros::Time &time, const ros::Duration &period) override
Definition: hw_interface.cpp:164
simple_client_goal_state.h
hardware_interface::JointStateHandle
ROS_ERROR
#define ROS_ERROR(...)
examples::HWInterface::jnt_state_interface_
hardware_interface::JointStateInterface jnt_state_interface_
Definition: hw_interface.h:120
examples::HWInterface::handleCartesianDone
void handleCartesianDone(const actionlib::SimpleClientGoalState &state, const cartesian_control_msgs::FollowCartesianTrajectoryResultConstPtr &result)
Definition: hw_interface.cpp:240
hardware_interface::CartesianTrajectory
cartesian_control_msgs::FollowCartesianTrajectoryGoal CartesianTrajectory
TrajectoryType for Cartesian trajectories.
Definition: trajectory_interface.h:63
examples::HWInterface::speedsc_interface_
scaled_controllers::SpeedScalingInterface speedsc_interface_
Definition: hw_interface.h:124
ResourceManager< JointStateHandle >::registerHandle
void registerHandle(const JointStateHandle &handle)
examples::HWInterface::handleCartesianFeedback
void handleCartesianFeedback(const cartesian_control_msgs::FollowCartesianTrajectoryFeedbackConstPtr &feedback)
Definition: hw_interface.cpp:234
hardware_interface::ExecutionState::PREEMPTED
@ PREEMPTED
examples::HWInterface::frame_id_
std::string frame_id_
Definition: hw_interface.h:136
simple_goal_state.h
hardware_interface::JointHandle
ros::Time
examples::HWInterface::joint_state_handles_
std::vector< hardware_interface::JointStateHandle > joint_state_handles_
Definition: hw_interface.h:166
examples::HWInterface::HWInterface
HWInterface()
Definition: hw_interface.cpp:43
examples::HWInterface::joint_handles_
std::vector< hardware_interface::JointHandle > joint_handles_
Definition: hw_interface.h:165
hardware_interface::JointTrajectory
control_msgs::FollowJointTrajectoryGoal JointTrajectory
TrajectoryType for joint-based trajectories.
Definition: trajectory_interface.h:58
examples::HWInterface::pose_cmd_interface_
ros_controllers_cartesian::PoseCommandInterface pose_cmd_interface_
Definition: hw_interface.h:119
hardware_interface::ExecutionState::ABORTED
@ ABORTED
examples::HWInterface::~HWInterface
~HWInterface()
Definition: hw_interface.cpp:155
examples::HWInterface::joint_names_
std::vector< std::string > joint_names_
Actuated joints in order from base to tip.
Definition: hw_interface.h:115
examples
Definition: hw_interface.cpp:41
hardware_interface::TrajectoryInterface::setFeedback
void setFeedback(FeedbackType feedback)
Set trajectory feedback for PassThroughControllers.
Definition: trajectory_interface.h:192
examples::HWInterface::cartesian_based_communication_
std::unique_ptr< actionlib::SimpleActionClient< cartesian_control_msgs::FollowCartesianTrajectoryAction > > cartesian_based_communication_
Definition: hw_interface.h:176
actionlib::SimpleClientGoalState::PREEMPTED
PREEMPTED
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
examples::HWInterface::eff_
std::vector< double > eff_
Definition: hw_interface.h:130
examples::HWInterface::handleJointFeedback
void handleJointFeedback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &feedback)
Definition: hw_interface.cpp:211
ROS_INFO
#define ROS_INFO(...)
ros::Duration
examples::HWInterface::dynamicReconfigureCallback
void dynamicReconfigureCallback(SpeedScalingConfig &config, uint32_t level)
Use dynamic reconfigure to mimic the driver's speed scaling.
Definition: hw_interface.cpp:205
examples::HWInterface::startCartesianInterpolation
void startCartesianInterpolation(const hardware_interface::CartesianTrajectory &trajectory)
Dummy implementation for Cartesian interpolation on the robot.
Definition: hw_interface.cpp:177
examples::HWInterface::cartesian_accel_
geometry_msgs::Accel cartesian_accel_
Definition: hw_interface.h:161
ros::NodeHandle


pass_through_controllers
Author(s):
autogenerated on Tue Oct 15 2024 02:10:52