#include <jog_frame_node.h>
Public Member Functions | |
int | get_controller_list () |
void | jog_frame_cb (jog_msgs::JogFrameConstPtr msg) |
Callback function for the topic jog_frame. More... | |
JogFrameNode () | |
void | joint_state_cb (sensor_msgs::JointStateConstPtr msg) |
Callback function for the topic joint_state. More... | |
Protected Attributes | |
std::map< std::string, Controller > | cinfo_map_ |
std::vector< std::string > | exclude_joints_ |
ros::ServiceClient | fk_client_ |
std::string | group_name_ |
ros::ServiceClient | ik_client_ |
bool | intermittent_ |
ros::Subscriber | jog_frame_sub_ |
std::map< std::string, double > | joint_map_ |
sensor_msgs::JointState | joint_state_ |
ros::Subscriber | joint_state_sub_ |
ros::Time | last_stamp_ |
geometry_msgs::PoseStamped | pose_stamped_ |
std::string | target_link_ |
double | time_from_start_ |
std::map< std::string, TrajClient * > | traj_clients_ |
std::map< std::string, ros::Publisher > | traj_pubs_ |
bool | use_action_ |
Class JogFrameNode - Provides the jog_frame
Definition at line 35 of file jog_frame_node.h.
jog_frame::JogFrameNode::JogFrameNode | ( | ) |
: Default constructor for JogFrameNode Class.
Definition at line 76 of file jog_frame_node.cpp.
int jog_frame::JogFrameNode::get_controller_list | ( | ) |
Definition at line 6 of file jog_frame_node.cpp.
void jog_frame::JogFrameNode::jog_frame_cb | ( | jog_msgs::JogFrameConstPtr | msg | ) |
Callback function for the topic jog_frame.
Definition at line 161 of file jog_frame_node.cpp.
void jog_frame::JogFrameNode::joint_state_cb | ( | sensor_msgs::JointStateConstPtr | msg | ) |
Callback function for the topic joint_state.
Definition at line 379 of file jog_frame_node.cpp.
|
protected |
Definition at line 50 of file jog_frame_node.h.
|
protected |
Definition at line 63 of file jog_frame_node.h.
|
protected |
Definition at line 48 of file jog_frame_node.h.
|
protected |
Definition at line 62 of file jog_frame_node.h.
|
protected |
Definition at line 48 of file jog_frame_node.h.
|
protected |
Definition at line 59 of file jog_frame_node.h.
|
protected |
Definition at line 47 of file jog_frame_node.h.
|
protected |
Definition at line 54 of file jog_frame_node.h.
|
protected |
Definition at line 64 of file jog_frame_node.h.
|
protected |
Definition at line 47 of file jog_frame_node.h.
|
protected |
Definition at line 65 of file jog_frame_node.h.
|
protected |
Definition at line 55 of file jog_frame_node.h.
|
protected |
Definition at line 61 of file jog_frame_node.h.
|
protected |
Definition at line 57 of file jog_frame_node.h.
|
protected |
Definition at line 51 of file jog_frame_node.h.
|
protected |
Definition at line 52 of file jog_frame_node.h.
|
protected |
Definition at line 58 of file jog_frame_node.h.