Go to the documentation of this file.
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"
50 <<
" from parameter server");
51 throw std::logic_error(
"Failed to initialize ros control.");
64 reconfig_server_ = std::make_shared<dynamic_reconfigure::Server<SpeedScalingConfig> >(nh);
68 cmd_.resize(nr_joints);
69 pos_.resize(nr_joints);
70 vel_.resize(nr_joints);
71 eff_.resize(nr_joints);
74 for (
int i = 0; i < nr_joints; ++i)
96 for (
int i = 0; i < nr_joints; ++i)
125 std::make_unique<actionlib::SimpleActionClient<control_msgs::FollowJointTrajectoryAction> >(
"joint_trajectory_"
132 std::make_unique<actionlib::SimpleActionClient<cartesian_control_msgs::FollowCartesianTrajectoryAction> >(
"cartes"
148 ROS_ERROR(
"Trajectory action interfaces of the robot dummy are not available.");
152 ROS_INFO(
"Example HW interface is ready");
217 const control_msgs::FollowJointTrajectoryResultConstPtr& result)
225 if (result->error_code == control_msgs::FollowJointTrajectoryResult::SUCCESSFUL)
235 const cartesian_control_msgs::FollowCartesianTrajectoryFeedbackConstPtr& feedback)
241 const cartesian_control_msgs::FollowCartesianTrajectoryResultConstPtr& result)
249 if (result->error_code == control_msgs::FollowJointTrajectoryResult::SUCCESSFUL)
geometry_msgs::Pose pose_cmd_
std::vector< double > pos_
std::vector< double > cmd_
void startJointInterpolation(const hardware_interface::JointTrajectory &trajectory)
Dummy implementation for joint interpolation on the robot.
std::string ref_frame_id_
#define ROS_ERROR_STREAM(args)
geometry_msgs::Pose cartesian_pose_
void registerCancelCallback(std::function< void()> f)
Register a RobotHW-side callback for canceling requests.
dynamic_reconfigure::Server< SpeedScalingConfig >::CallbackType callback_type_
JointStateHandle getHandle(const std::string &name)
geometry_msgs::Accel cartesian_jerk_
std::unique_ptr< actionlib::SimpleActionClient< control_msgs::FollowJointTrajectoryAction > > joint_based_communication_
bool getParam(const std::string &key, bool &b) const
void registerInterface(T *iface)
ros_controllers_cartesian::CartesianStateInterface cart_state_interface_
geometry_msgs::Twist cartesian_twist_
void read(const ros::Time &time, const ros::Duration &period) override
pass_through_controllers::SpeedScalingConfig SpeedScalingConfig
hardware_interface::CartesianTrajectoryInterface cart_traj_interface_
hardware_interface::PositionJointInterface jnt_pos_interface_
void handleJointDone(const actionlib::SimpleClientGoalState &state, const control_msgs::FollowJointTrajectoryResultConstPtr &result)
void cancelJointInterpolation()
Dummy implementation for canceling a running joint interpolation on the robot.
void setDone(const ExecutionState &state)
RobotHW-side method to mark the execution of a trajectory done.
hardware_interface::JointTrajectoryInterface jnt_traj_interface_
std::vector< double > vel_
std::shared_ptr< dynamic_reconfigure::Server< SpeedScalingConfig > > reconfig_server_
void registerGoalCallback(std::function< void(const TrajectoryType &)> f)
Register a RobotHW-side callback for new trajectory execution.
void cancelCartesianInterpolation()
Dummy implementation for canceling a running Cartesian interpolation on the robot.
void write(const ros::Time &time, const ros::Duration &period) override
hardware_interface::JointStateInterface jnt_state_interface_
void handleCartesianDone(const actionlib::SimpleClientGoalState &state, const cartesian_control_msgs::FollowCartesianTrajectoryResultConstPtr &result)
cartesian_control_msgs::FollowCartesianTrajectoryGoal CartesianTrajectory
TrajectoryType for Cartesian trajectories.
scaled_controllers::SpeedScalingInterface speedsc_interface_
void registerHandle(const JointStateHandle &handle)
void handleCartesianFeedback(const cartesian_control_msgs::FollowCartesianTrajectoryFeedbackConstPtr &feedback)
std::vector< hardware_interface::JointStateHandle > joint_state_handles_
std::vector< hardware_interface::JointHandle > joint_handles_
control_msgs::FollowJointTrajectoryGoal JointTrajectory
TrajectoryType for joint-based trajectories.
ros_controllers_cartesian::PoseCommandInterface pose_cmd_interface_
std::vector< std::string > joint_names_
Actuated joints in order from base to tip.
void setFeedback(FeedbackType feedback)
Set trajectory feedback for PassThroughControllers.
std::unique_ptr< actionlib::SimpleActionClient< cartesian_control_msgs::FollowCartesianTrajectoryAction > > cartesian_based_communication_
const std::string & getNamespace() const
std::vector< double > eff_
void handleJointFeedback(const control_msgs::FollowJointTrajectoryFeedbackConstPtr &feedback)
void dynamicReconfigureCallback(SpeedScalingConfig &config, uint32_t level)
Use dynamic reconfigure to mimic the driver's speed scaling.
void startCartesianInterpolation(const hardware_interface::CartesianTrajectory &trajectory)
Dummy implementation for Cartesian interpolation on the robot.
geometry_msgs::Accel cartesian_accel_