TeleopCOB Class Reference

Implementation of teleoperation node. More...

List of all members.

Classes

struct  base_module_struct
struct  combined_joints_struct
struct  joint_module

Public Member Functions

void getConfigurationFromParameters ()
void init ()
 Initializes node to get parameters, subscribe to topics.
void joint_states_cb (const sensor_msgs::JointState::ConstPtr &joint_states_msg)
 Executes the callback from the joint_states topic. (published by joint state driver).
void joy_cb (const joy::Joy::ConstPtr &joy_msg)
 Executes the callback from the joystick topic.
void setInitValues ()
 Sets initial values for target velocities.
 TeleopCOB ()
 Constructor for TeleopCOB class.
void update ()
 Main routine for updating all components.
void update_base ()
 Routine for updating the base commands.
void update_joint_modules ()
void waitForParameters ()
 ~TeleopCOB ()
 Destructor for TeleopCOB class.

Public Attributes

int arm_joint12_button_
int arm_joint34_button_
int arm_joint56_button_
int arm_joint7_button_
int axis_vth_
int axis_vx_
int axis_vy_
struct
TeleopCOB::base_module_struct 
base_module_
struct
TeleopCOB::combined_joints_struct 
combined_joints_
int deadman_button_
bool got_init_values_
bool has_base_module_
std::vector< double > joint_init_values_
std::map< std::string,
joint_module
joint_modules_
std::vector< std::string > joint_names_
ros::Subscriber joint_states_sub_
bool joy_active_
ros::Subscriber joy_sub_
int left_right_
int lower_neck_button_
ros::NodeHandle n_
int recover_base_button_
int run_button_
double run_factor_
double run_factor_param_
int stop_base_button_
bool stopped_
double time_for_init_
int tray_button_
int up_down_
int upper_neck_button_

Private Member Functions

bool assign_base_module (XmlRpc::XmlRpcValue)
bool assign_joint_module (std::string, XmlRpc::XmlRpcValue)

Detailed Description

Implementation of teleoperation node.

Sends direct commands to different components

Definition at line 85 of file cob_teleop.cpp.


Constructor & Destructor Documentation

TeleopCOB::TeleopCOB (  ) 

Constructor for TeleopCOB class.

Definition at line 361 of file cob_teleop.cpp.

TeleopCOB::~TeleopCOB (  ) 

Destructor for TeleopCOB class.

Definition at line 386 of file cob_teleop.cpp.


Member Function Documentation

bool TeleopCOB::assign_base_module ( XmlRpc::XmlRpcValue  mod_struct  )  [private]

Tries to read base module configurations from XmlRpcValue object. A base module is supposed to contain vectors 3 element vectors (x,y,th) with max acceleration and velocity. Example: struct { max_velocity: [0.3, 0.2, 0.3], max_acceleration: [0.5, 0.5, 0.7] }

Parameters:
mod_struct configuration object struct
Returns:
true no check is currently performed TODO check

Definition at line 303 of file cob_teleop.cpp.

bool TeleopCOB::assign_joint_module ( std::string  mod_name,
XmlRpc::XmlRpcValue  mod_struct 
) [private]

Tries to read joint module configurations from XmlRpcValue object. If the module is a joint module, it contains a joint name array. A typical joint module has the following configuration structure: struct { joint_names: ['head_pan_joint','head_tilt_joint'], joint_step: 0.075 }

Parameters:
mod_struct configuration object struct
Returns:
true if the configuration object hols a joint module config, else false

Definition at line 233 of file cob_teleop.cpp.

void TeleopCOB::getConfigurationFromParameters (  ) 

Definition at line 188 of file cob_teleop.cpp.

void TeleopCOB::init (  ) 

Initializes node to get parameters, subscribe to topics.

Definition at line 393 of file cob_teleop.cpp.

void TeleopCOB::joint_states_cb ( const sensor_msgs::JointState::ConstPtr &  joint_states_msg  ) 

Executes the callback from the joint_states topic. (published by joint state driver).

Only used to get the initaial joint positions.

Parameters:
msg JointState

Definition at line 475 of file cob_teleop.cpp.

void TeleopCOB::joy_cb ( const joy::Joy::ConstPtr &  joy_msg  ) 

Executes the callback from the joystick topic.

Gets the configuration

Parameters:
joy_msg Joy

Definition at line 507 of file cob_teleop.cpp.

void TeleopCOB::setInitValues (  ) 

Sets initial values for target velocities.

Definition at line 445 of file cob_teleop.cpp.

void TeleopCOB::update (  ) 

Main routine for updating all components.

Definition at line 832 of file cob_teleop.cpp.

void TeleopCOB::update_base (  ) 

Routine for updating the base commands.

Definition at line 925 of file cob_teleop.cpp.

void TeleopCOB::update_joint_modules (  ) 

Definition at line 884 of file cob_teleop.cpp.

void TeleopCOB::waitForParameters (  ) 

Definition at line 158 of file cob_teleop.cpp.


Member Data Documentation

Definition at line 113 of file cob_teleop.cpp.

Definition at line 114 of file cob_teleop.cpp.

Definition at line 115 of file cob_teleop.cpp.

Definition at line 116 of file cob_teleop.cpp.

Definition at line 112 of file cob_teleop.cpp.

Definition at line 112 of file cob_teleop.cpp.

Definition at line 112 of file cob_teleop.cpp.

Definition at line 121 of file cob_teleop.cpp.

Definition at line 130 of file cob_teleop.cpp.

Definition at line 108 of file cob_teleop.cpp.

std::vector<double> TeleopCOB::joint_init_values_

Definition at line 139 of file cob_teleop.cpp.

std::map<std::string,joint_module> TeleopCOB::joint_modules_

Definition at line 98 of file cob_teleop.cpp.

std::vector<std::string> TeleopCOB::joint_names_

Definition at line 138 of file cob_teleop.cpp.

Definition at line 128 of file cob_teleop.cpp.

Definition at line 122 of file cob_teleop.cpp.

ros::Subscriber TeleopCOB::joy_sub_

Definition at line 127 of file cob_teleop.cpp.

Definition at line 118 of file cob_teleop.cpp.

Definition at line 110 of file cob_teleop.cpp.

ros::NodeHandle TeleopCOB::n_

Definition at line 126 of file cob_teleop.cpp.

Definition at line 121 of file cob_teleop.cpp.

Definition at line 121 of file cob_teleop.cpp.

Definition at line 123 of file cob_teleop.cpp.

Definition at line 123 of file cob_teleop.cpp.

Definition at line 121 of file cob_teleop.cpp.

Definition at line 122 of file cob_teleop.cpp.

Definition at line 131 of file cob_teleop.cpp.

Definition at line 111 of file cob_teleop.cpp.

Definition at line 118 of file cob_teleop.cpp.

Definition at line 110 of file cob_teleop.cpp.


The documentation for this class was generated from the following file:
 All Classes Files Functions Variables Defines


cob_teleop
Author(s): Florian Weisshardt
autogenerated on Fri Jan 11 10:00:36 2013