Go to the documentation of this file.
31 pub_ = nh.
advertise<std_msgs::Float64MultiArray>(
"joint_group_velocity_controller/command", 1);
37 const KDL::JntArray& current_q)
39 std_msgs::Float64MultiArray vel_msg;
43 vel_msg.data.push_back(q_dot_ik(i));
59 pub_ = nh.
advertise<std_msgs::Float64MultiArray>(
"joint_group_position_controller/command", 1);
65 const KDL::JntArray& current_q)
70 std_msgs::Float64MultiArray pos_msg;
86 pub_ = nh.
advertise<trajectory_msgs::JointTrajectory>(
"joint_trajectory_controller/command", 1);
92 const KDL::JntArray& current_q)
96 trajectory_msgs::JointTrajectoryPoint traj_point;
97 traj_point.positions =
pos_;
101 traj_point.time_from_start =
period_;
103 trajectory_msgs::JointTrajectory traj_msg;
106 traj_msg.points.push_back(traj_point);
123 pub_ = nh.
advertise<sensor_msgs::JointState>(
"joint_states", 1);
148 js_msg_.position.push_back(pos);
149 js_msg_.velocity.push_back(0.0);
160 const KDL::JntArray& current_q)
165 boost::mutex::scoped_lock lock(
mutex_);
178 boost::mutex::scoped_lock lock(
mutex_);
virtual void initialize(ros::NodeHandle &nh, const TwistControllerParams ¶ms)
virtual void initialize(ros::NodeHandle &nh, const TwistControllerParams ¶ms)
std::vector< double > limits_min
virtual void processResult(const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_q)
Class providing a ControllerInterface publishing JointStates.
std::vector< double > pos_
LimiterParams limiter_params
double integrator_smoothing
virtual void initialize(ros::NodeHandle &nh, const TwistControllerParams ¶ms)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
Base class for controller interfaces.
boost::shared_ptr< SimpsonIntegrator > integrator_
void publishJointState(const ros::TimerEvent &event)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Class providing a ControllerInterface publishing JointGroupPositionCommands.
Class providing a ControllerInterface publishing velocities.
virtual void processResult(const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_q)
Class providing a ControllerInterface publishing a JointTrajectory.
std::vector< std::string > joints
ros::Time last_update_time_
sensor_msgs::JointState js_msg_
virtual void initialize(ros::NodeHandle &nh, const TwistControllerParams ¶ms)
virtual void processResult(const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_q)
bool updateIntegration(const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_q)
virtual void processResult(const KDL::JntArray &q_dot_ik, const KDL::JntArray ¤t_q)
TwistControllerParams params_
std::vector< double > limits_max
std::vector< double > vel_
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
cob_twist_controller
Author(s): Felix Messmer
, Marco Bezzon , Christoph Mark , Francisco Moreno
autogenerated on Mon May 1 2023 02:44:43