Public Types | Public Member Functions | Private Member Functions | Private Attributes
controller::JointGroupPositionController Class Reference

Controls the position of a group of joints using a pid loop. More...

#include <joint_group_position_controller.h>

Inheritance diagram for controller::JointGroupPositionController:
Inheritance graph
[legend]

List of all members.

Public Types

typedef std::vector< double > JointErrorList
typedef std::vector< double > JointPosList
typedef std::vector< int > JointStateToCmd
typedef std::vector
< control_toolbox::Pid
PidList

Public Member Functions

bool init (pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n)
 JointGroupPositionController ()
virtual void starting ()
virtual void update ()
 ~JointGroupPositionController ()

Private Member Functions

void commandCB (const sensor_msgs::JointState::ConstPtr &command)

Private Attributes

JointErrorList errors_
std::vector
< pr2_mechanism_model::JointState * > 
joints_
ros::Time last_time_
JointStateToCmd lookup_
ros::NodeHandle node_
PidList pids_
JointPosList ref_pos_
pr2_mechanism_model::RobotStaterobot_
ros::Subscriber sub_command_

Detailed Description

Controls the position of a group of joints using a pid loop.

Author:
Adolfo Rodriguez Tsouroukdissian. This class is heavily inspired on the structure of the JointSplineTrajectoryController written by Stuart Glaser, and the JointPositionController.

Definition at line 61 of file joint_group_position_controller.h.


Member Typedef Documentation

Definition at line 65 of file joint_group_position_controller.h.

Definition at line 66 of file joint_group_position_controller.h.

Definition at line 67 of file joint_group_position_controller.h.

Definition at line 64 of file joint_group_position_controller.h.


Constructor & Destructor Documentation

Definition at line 52 of file joint_group_position_controller.cpp.

Definition at line 56 of file joint_group_position_controller.cpp.


Member Function Documentation

void controller::JointGroupPositionController::commandCB ( const sensor_msgs::JointState::ConstPtr &  command) [private]

Definition at line 167 of file joint_group_position_controller.cpp.

Reimplemented from pr2_controller_interface::Controller.

Definition at line 129 of file joint_group_position_controller.cpp.


Member Data Documentation

Definition at line 83 of file joint_group_position_controller.h.

Definition at line 80 of file joint_group_position_controller.h.

Definition at line 79 of file joint_group_position_controller.h.

Definition at line 84 of file joint_group_position_controller.h.

Definition at line 86 of file joint_group_position_controller.h.

Definition at line 81 of file joint_group_position_controller.h.

Definition at line 82 of file joint_group_position_controller.h.

Definition at line 78 of file joint_group_position_controller.h.

Definition at line 89 of file joint_group_position_controller.h.


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


joint_group_position_controller
Author(s): Adolfo Rodriguez Tsouroukdissian
autogenerated on Thu Jan 2 2014 11:41:12