Public Member Functions | Private Member Functions | Private Attributes
JointPositionController Class Reference

A simple joint position controller, which controls each joint independently of each other using a PD control scheme. More...

#include <joint_position_controller.h>

List of all members.

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::RobotStaterobot_state_
ros::Subscriber sub_joint_states_cmd
KDL::JntArray tau_
KDL::JntArray tau_max_
pr2_mechanism_model::Tree tree_

Detailed Description

A simple joint position controller, which controls each joint independently of each other using a PD control scheme.

Author:
Marcus Liebhardt This joint position controller tries to minimise the position error of all joints in the given KDL::Tree. In doing so, all joints are controlled independently. It also limits the calculated efforts as well as joint position errors. The desired joint positions are received from a topic.

Definition at line 53 of file joint_position_controller.h.


Member Function Documentation

Initialises the controller and loads all necessary parameters.

Initialises the controller and loads all necessary parameters

Parameters:
robot_statepointer to the robot state
nhnode handle
Returns:
always true

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

Parameters:
commandpointer to sensor_msgs::JointState message containing the new desired joint positions

Definition at line 46 of file joint_position_controller.cpp.

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.

Stops the controller (in real-time)

Definition at line 261 of file joint_position_controller.cpp.

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.


Member Data Documentation

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.

Definition at line 96 of file joint_position_controller.h.

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.

Definition at line 101 of file joint_position_controller.h.

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.


The documentation for this class was generated from the following files:


joint_position_controller
Author(s): Marcus Liebhardt
autogenerated on Mon Jan 6 2014 11:40:20