Public Member Functions | Private Types | Private Attributes
CobControlModeAdapter Class Reference

List of all members.

Public Member Functions

void cmd_pos_cb (const std_msgs::Float64MultiArray::ConstPtr &msg)
void cmd_vel_cb (const std_msgs::Float64MultiArray::ConstPtr &msg)
bool initialize ()
bool loadController (std::string load_controller)
bool switchController (std::vector< std::string > start_controllers, std::vector< std::string > stop_controllers)
void update (const ros::TimerEvent &event)

Private Types

enum  { NONE, VELOCITY, POSITION, TRAJECTORY }

Private Attributes

ros::Subscriber cmd_pos_sub_
ros::Subscriber cmd_vel_sub_
enum CobControlModeAdapter:: { ... }  current_control_mode_
std::vector< std::string > current_controller_names_
bool has_pos_controller_
bool has_traj_controller_
bool has_vel_controller_
std::vector< std::string > joint_names_
ros::Time last_pos_command_
ros::Time last_vel_command_
ros::ServiceClient load_client_
double max_command_silence_
boost::mutex mutex_
ros::NodeHandle nh_
std::vector< std::string > pos_controller_names_
ros::ServiceClient switch_client_
ros::Timer timer_
std::vector< std::string > traj_controller_names_
double update_rate_
std::vector< std::string > vel_controller_names_

Detailed Description

Definition at line 27 of file cob_control_mode_adapter_node.cpp.


Member Enumeration Documentation

anonymous enum [private]
Enumerator:
NONE 
VELOCITY 
POSITION 
TRAJECTORY 

Definition at line 325 of file cob_control_mode_adapter_node.cpp.


Member Function Documentation

void CobControlModeAdapter::cmd_pos_cb ( const std_msgs::Float64MultiArray::ConstPtr &  msg) [inline]

Definition at line 232 of file cob_control_mode_adapter_node.cpp.

void CobControlModeAdapter::cmd_vel_cb ( const std_msgs::Float64MultiArray::ConstPtr &  msg) [inline]

Definition at line 238 of file cob_control_mode_adapter_node.cpp.

Definition at line 30 of file cob_control_mode_adapter_node.cpp.

bool CobControlModeAdapter::loadController ( std::string  load_controller) [inline]

Definition at line 158 of file cob_control_mode_adapter_node.cpp.

bool CobControlModeAdapter::switchController ( std::vector< std::string >  start_controllers,
std::vector< std::string >  stop_controllers 
) [inline]

Definition at line 183 of file cob_control_mode_adapter_node.cpp.

void CobControlModeAdapter::update ( const ros::TimerEvent event) [inline]

Definition at line 244 of file cob_control_mode_adapter_node.cpp.


Member Data Documentation

Definition at line 339 of file cob_control_mode_adapter_node.cpp.

Definition at line 340 of file cob_control_mode_adapter_node.cpp.

std::vector< std::string > CobControlModeAdapter::current_controller_names_ [private]

Definition at line 330 of file cob_control_mode_adapter_node.cpp.

Definition at line 336 of file cob_control_mode_adapter_node.cpp.

Definition at line 335 of file cob_control_mode_adapter_node.cpp.

Definition at line 337 of file cob_control_mode_adapter_node.cpp.

std::vector< std::string > CobControlModeAdapter::joint_names_ [private]

Definition at line 323 of file cob_control_mode_adapter_node.cpp.

Definition at line 346 of file cob_control_mode_adapter_node.cpp.

Definition at line 347 of file cob_control_mode_adapter_node.cpp.

Definition at line 342 of file cob_control_mode_adapter_node.cpp.

Definition at line 345 of file cob_control_mode_adapter_node.cpp.

boost::mutex CobControlModeAdapter::mutex_ [private]

Definition at line 348 of file cob_control_mode_adapter_node.cpp.

Definition at line 318 of file cob_control_mode_adapter_node.cpp.

std::vector< std::string > CobControlModeAdapter::pos_controller_names_ [private]

Definition at line 332 of file cob_control_mode_adapter_node.cpp.

Definition at line 343 of file cob_control_mode_adapter_node.cpp.

Definition at line 320 of file cob_control_mode_adapter_node.cpp.

std::vector< std::string > CobControlModeAdapter::traj_controller_names_ [private]

Definition at line 331 of file cob_control_mode_adapter_node.cpp.

Definition at line 321 of file cob_control_mode_adapter_node.cpp.

std::vector< std::string > CobControlModeAdapter::vel_controller_names_ [private]

Definition at line 333 of file cob_control_mode_adapter_node.cpp.


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


cob_control_mode_adapter
Author(s): Felix Messmer
autogenerated on Thu Jun 6 2019 21:18:59