45 JointPositionController::JointPositionController()
46 : joint_state_(NULL), command_(0),
47 loop_count_(0), initialized_(false), robot_(NULL), last_time_(0)
66 ROS_ERROR(
"JointPositionController could not find joint named \"%s\"\n",
72 ROS_ERROR(
"Joint %s not calibrated for JointPositionController", joint_name.c_str());
86 std::string joint_name;
102 return init(robot, joint_name, pid);
PLUGINLIB_EXPORT_CLASS(my_controller_ns::MyControllerClass, pr2_controller_interface::Controller)
void setCommand(double cmd)
Give set position of the joint for next update: revolute (angle) and prismatic (position) ...
~JointPositionController()
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string getJointName()
void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
ros::Subscriber sub_command_
boost::scoped_ptr< realtime_tools::RealtimePublisher< pr2_controllers_msgs::JointControllerState > > controller_state_publisher_
pr2_mechanism_model::RobotState * robot_
boost::shared_ptr< const urdf::Joint > joint_
pr2_mechanism_model::JointState * joint_state_
control_toolbox::Pid pid_controller_
void setCommandCB(const std_msgs::Float64ConstPtr &msg)
const std::string & getNamespace() const
JointState * getJointState(const std::string &name)
void getCommand(double &cmd)
Get latest position command to the joint: revolute (angle) and prismatic (position).
bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name, const control_toolbox::Pid &pid)
def shortest_angular_distance_with_limits(from_angle, to_angle, left_limit, right_limit)
void getGains(double &p, double &i, double &d, double &i_max, double &i_min)
bool getParam(const std::string &key, std::string &s) const
virtual void update()
Issues commands to the joint. Should be called at regular intervals.
def shortest_angular_distance(from_angle, to_angle)