60 std::string joint_name;
61 if (!n.
getParam(
"joint", joint_name))
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 )
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void starting(const ros::Time &time)
This is called from within the realtime thread just before the first call to update.
URDF_EXPORT bool initParamWithNodeHandle(const std::string ¶m, const ros::NodeHandle &nh=ros::NodeHandle())
double getVelocity() const
ros::Subscriber sub_command_
JointPositionController()
void printDebug()
Print debug info to console.
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...
Joint Position Controller.
bool getParam(const std::string &key, std::string &s) const
std::unique_ptr< realtime_tools::RealtimePublisher< control_msgs::JointControllerState > > controller_state_publisher_
void update(const ros::Time &time, const ros::Duration &period)
Issues commands to the joint. Should be called at regular intervals.
control_toolbox::Pid pid_controller_
hardware_interface::JointHandle joint_
realtime_tools::RealtimeBuffer< Commands > command_
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
Callback from /command subscriber for setpoint.
JointHandle getHandle(const std::string &name)
void setCommand(double command)
double getPosition()
Get the current position of the joint.
const std::string & getNamespace() const
~JointPositionController()
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
Get the PID parameters.
void setCommand(double pos_target)
Give set position of the joint for next update: revolute (angle) and prismatic (position) ...
void enforceJointLimits(double &command)
Check that the command is within the hard limits of the joint. Checks for joint type first...
std::string getJointName()
Get the name of the joint this controller uses.
urdf::JointConstSharedPtr joint_urdf_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
std::string getName() const
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.
def shortest_angular_distance(from_angle, to_angle)
def shortest_angular_distance_with_large_limits(from_angle, to_angle, left_limit, right_limit)
double getPosition() const