64 std::string param_name =
"joints";
99 urdf::JointConstSharedPtr joint_urdf = urdf.getJoint(
joint_names_[i]);
126 double command_position = commands[i];
129 double commanded_effort;
131 double current_position =
joints_[i].getPosition();
146 else if (
joint_urdfs_[i]->type == urdf::Joint::CONTINUOUS)
152 error = command_position - current_position;
159 joints_[i].setCommand(commanded_effort);
167 ROS_ERROR_STREAM(
"Dimension of command (" << msg->data.size() <<
") does not match number of joints (" <<
n_joints_ <<
")! Not executing!");
virtual const char * what() const
~JointGroupPositionController()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::vector< hardware_interface::JointHandle > joints_
void commandCB(const std_msgs::Float64MultiArrayConstPtr &msg)
Forward command controller for a set of effort controlled joints (torque or force).
JointGroupPositionController()
Forward command controller for a set of effort controlled joints (torque or force).
void enforceJointLimits(double &command, unsigned int index)
void update(const ros::Time &, const ros::Duration &)
std::vector< std::string > joint_names_
const std::string & getNamespace() const
ros::Subscriber sub_command_
URDF_EXPORT bool initParam(const std::string ¶m)
std::vector< control_toolbox::Pid > pid_controllers_
realtime_tools::RealtimeBuffer< std::vector< double > > commands_buffer_
def shortest_angular_distance_with_limits(from_angle, to_angle, left_limit, right_limit)
JointHandle getHandle(const std::string &name)
std::vector< urdf::JointConstSharedPtr > joint_urdfs_
bool getParam(const std::string &key, std::string &s) const
#define ROS_ERROR_STREAM(args)
bool init(hardware_interface::EffortJointInterface *hw, ros::NodeHandle &n)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
def shortest_angular_distance(from_angle, to_angle)