A simple joint position controller, which controls each joint independently of each other using a PD control scheme. More...
#include <joint_position_controller.h>
Public Member Functions | |
bool | init (pr2_mechanism_model::RobotState *robot_state, ros::NodeHandle &nh) |
Initialises the controller and loads all necessary parameters. | |
void | starting () |
Starts the controller in real-time and resets the used data structures. | |
void | stopping () |
void | update () |
Update loop of the controller (in real-time) | |
Private Member Functions | |
void | jointStatesCmdCB (const sensor_msgs::JointState::ConstPtr &command) |
callback function for the subscriber, which receives the desired joint positions | |
Private Attributes | |
double | dt_ |
KDL::JntArray | Kd_ |
KDL::JntArray | Kp_ |
ros::Time | last_time_ |
bool | limit_error_ |
unsigned int | loop_count_ |
unsigned int | nrOfJnts_ |
KDL::JntArray | q_ |
KDL::JntArray | q_desi_ |
KDL::JntArray | q_err_ |
KDL::JntArray | q_err_dot_ |
double | q_err_dot_max_ |
double | q_err_max_ |
KDL::JntArray | q_err_old_ |
pr2_mechanism_model::RobotState * | robot_state_ |
ros::Subscriber | sub_joint_states_cmd |
KDL::JntArray | tau_ |
KDL::JntArray | tau_max_ |
pr2_mechanism_model::Tree | tree_ |
A simple joint position controller, which controls each joint independently of each other using a PD control scheme.
Definition at line 53 of file joint_position_controller.h.
bool JointPositionController::init | ( | pr2_mechanism_model::RobotState * | robot_state, |
ros::NodeHandle & | nh | ||
) |
Initialises the controller and loads all necessary parameters.
Initialises the controller and loads all necessary parameters
robot_state | pointer to the robot state |
nh | node handle |
Pick the gains
Definition at line 62 of file joint_position_controller.cpp.
void JointPositionController::jointStatesCmdCB | ( | const sensor_msgs::JointState::ConstPtr & | command | ) | [private] |
callback function for the subscriber, which receives the desired joint positions
callback function for the subscriber, which receives the desired joint positions
command | pointer to sensor_msgs::JointState message containing the new desired joint positions |
Definition at line 46 of file joint_position_controller.cpp.
void JointPositionController::starting | ( | ) |
Starts the controller in real-time and resets the used data structures.
Starts the controller in real time and resets the used data structures; the initialisation of the controller runs in non-real-time.
Definition at line 148 of file joint_position_controller.cpp.
void JointPositionController::stopping | ( | ) |
Stops the controller (in real-time)
Definition at line 261 of file joint_position_controller.cpp.
void JointPositionController::update | ( | ) |
Update loop of the controller (in real-time)
The update loop determines the current position error of each joints and calculates the joint efforts to minimise the position error. Joint position error and effort limiting is also done here. The update loop also runs in real-time.
Definition at line 162 of file joint_position_controller.cpp.
double JointPositionController::dt_ [private] |
Definition at line 97 of file joint_position_controller.h.
KDL::JntArray JointPositionController::Kd_ [private] |
Definition at line 110 of file joint_position_controller.h.
KDL::JntArray JointPositionController::Kp_ [private] |
Definition at line 109 of file joint_position_controller.h.
ros::Time JointPositionController::last_time_ [private] |
Definition at line 96 of file joint_position_controller.h.
bool JointPositionController::limit_error_ [private] |
Definition at line 99 of file joint_position_controller.h.
unsigned int JointPositionController::loop_count_ [private] |
Definition at line 98 of file joint_position_controller.h.
unsigned int JointPositionController::nrOfJnts_ [private] |
Definition at line 95 of file joint_position_controller.h.
KDL::JntArray JointPositionController::q_ [private] |
Definition at line 104 of file joint_position_controller.h.
KDL::JntArray JointPositionController::q_desi_ [private] |
Definition at line 105 of file joint_position_controller.h.
KDL::JntArray JointPositionController::q_err_ [private] |
Definition at line 106 of file joint_position_controller.h.
KDL::JntArray JointPositionController::q_err_dot_ [private] |
Definition at line 108 of file joint_position_controller.h.
double JointPositionController::q_err_dot_max_ [private] |
Definition at line 101 of file joint_position_controller.h.
double JointPositionController::q_err_max_ [private] |
Definition at line 100 of file joint_position_controller.h.
KDL::JntArray JointPositionController::q_err_old_ [private] |
Definition at line 107 of file joint_position_controller.h.
Definition at line 93 of file joint_position_controller.h.
Definition at line 114 of file joint_position_controller.h.
KDL::JntArray JointPositionController::tau_ [private] |
Definition at line 111 of file joint_position_controller.h.
KDL::JntArray JointPositionController::tau_max_ [private] |
Definition at line 112 of file joint_position_controller.h.
pr2_mechanism_model::Tree JointPositionController::tree_ [private] |
Definition at line 94 of file joint_position_controller.h.