Public Member Functions | Protected Attributes | List of all members
jog_joint::JogJointNode Class Reference

#include <jog_joint_node.h>

Public Member Functions

int get_controller_list ()
 
void jog_joint_cb (jog_msgs::JogJointConstPtr msg)
 Callback function for the topic jog_joint. More...
 
 JogJointNode ()
 
void joint_state_cb (sensor_msgs::JointStateConstPtr msg)
 Callback function for the topic joint_state. More...
 

Protected Attributes

std::map< std::string, Controllercinfo_map_
 
bool intermittent_
 
ros::Subscriber jog_joint_sub_
 
std::map< std::string, double > joint_map_
 
sensor_msgs::JointState joint_state_
 
ros::Publisher joint_state_pub_
 
ros::Subscriber joint_state_sub_
 
ros::Time last_stamp_
 
double time_from_start_
 
std::map< std::string, TrajClient * > traj_clients_
 
std::map< std::string, ros::Publishertraj_pubs_
 
bool use_action_
 

Detailed Description

Class JogJointNode - Provides the jog_joint

Definition at line 32 of file jog_joint_node.h.

Constructor & Destructor Documentation

jog_joint::JogJointNode::JogJointNode ( )

: Default constructor for JogJointNode Class.

Definition at line 75 of file jog_joint_node.cpp.

Member Function Documentation

int jog_joint::JogJointNode::get_controller_list ( )

Definition at line 5 of file jog_joint_node.cpp.

void jog_joint::JogJointNode::jog_joint_cb ( jog_msgs::JogJointConstPtr  msg)

Callback function for the topic jog_joint.

Definition at line 155 of file jog_joint_node.cpp.

void jog_joint::JogJointNode::joint_state_cb ( sensor_msgs::JointStateConstPtr  msg)

Callback function for the topic joint_state.

Definition at line 258 of file jog_joint_node.cpp.

Member Data Documentation

std::map<std::string, Controller> jog_joint::JogJointNode::cinfo_map_
protected

Definition at line 46 of file jog_joint_node.h.

bool jog_joint::JogJointNode::intermittent_
protected

Definition at line 57 of file jog_joint_node.h.

ros::Subscriber jog_joint::JogJointNode::jog_joint_sub_
protected

Definition at line 44 of file jog_joint_node.h.

std::map<std::string, double> jog_joint::JogJointNode::joint_map_
protected

Definition at line 51 of file jog_joint_node.h.

sensor_msgs::JointState jog_joint::JogJointNode::joint_state_
protected

Definition at line 52 of file jog_joint_node.h.

ros::Publisher jog_joint::JogJointNode::joint_state_pub_
protected

Definition at line 49 of file jog_joint_node.h.

ros::Subscriber jog_joint::JogJointNode::joint_state_sub_
protected

Definition at line 44 of file jog_joint_node.h.

ros::Time jog_joint::JogJointNode::last_stamp_
protected

Definition at line 54 of file jog_joint_node.h.

double jog_joint::JogJointNode::time_from_start_
protected

Definition at line 55 of file jog_joint_node.h.

std::map<std::string, TrajClient*> jog_joint::JogJointNode::traj_clients_
protected

Definition at line 47 of file jog_joint_node.h.

std::map<std::string, ros::Publisher> jog_joint::JogJointNode::traj_pubs_
protected

Definition at line 48 of file jog_joint_node.h.

bool jog_joint::JogJointNode::use_action_
protected

Definition at line 56 of file jog_joint_node.h.


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


jog_controller
Author(s): Ryosuke Tajima
autogenerated on Sun May 17 2020 03:25:01