Go to the documentation of this file.
60 std::string joint_name;
61 if (!n.
getParam(
"joint", joint_name))
83 if (!
urdf.initParamWithNodeHandle(
"robot_description", n))
91 ROS_ERROR(
"Could not find joint '%s' in urdf", joint_name.c_str());
173 double error, vel_error;
174 double commanded_effort;
191 else if (
joint_urdf_->type == urdf::Joint::CONTINUOUS)
197 error = command_position - current_position;
262 else if( command < joint_urdf_->limits->lower )
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min, const bool &antiwindup=false)
Set the PID parameters.
static double shortest_angular_distance(double from, double to)
JointPositionController()
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get the PID parameters.
ros::Subscriber sub_command_
JointHandle getHandle(const std::string &name)
bool getParam(const std::string &key, bool &b) const
ROSLIB_DECL std::string command(const std::string &cmd)
bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n)
The init function is called to initialize the controller from a non-realtime thread with a pointer to...
void setCommand(double command)
void starting(const ros::Time &time)
This is called from within the realtime thread just before the first call to update.
void printDebug()
Print debug info to console.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
control_toolbox::Pid pid_controller_
void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
hardware_interface::JointHandle joint_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
std::string getName() const
std::unique_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
urdf::JointConstSharedPtr joint_urdf_
void setCommand(double pos_target)
Give set position of the joint for next update: revolute (angle) and prismatic (position)
realtime_tools::RealtimeBuffer< Commands > command_
std::string getJointName()
Get the name of the joint this controller uses.
double getVelocity() const
void enforceJointLimits(double &command)
Check that the command is within the hard limits of the joint. Checks for joint type first....
double getPosition() const
Joint Position Controller.
static bool shortest_angular_distance_with_large_limits(double from, double to, double left_limit, double right_limit, double &shortest_angle)
const std::string & getNamespace() const
~JointPositionController()
double getPosition()
Get the current position of the joint.
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
Callback from /command subscriber for setpoint.