Public Member Functions | Private Member Functions | Private Attributes
JacoInteractiveManipulation Class Reference

#include <jaco_interactive_manipulation.h>

List of all members.

Public Member Functions

 JacoInteractiveManipulation ()
 Constructor.
void processHandMarkerFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
 Process feedback for the interactive marker on the JACO's end effector.
void updateJoints (const sensor_msgs::JointState::ConstPtr &msg)
 Callback for the joint state listener.
void updateMarkerPosition ()
 Update the interactive marker on the JACO's end effector to move based on the the current joint state of the arm.

Private Member Functions

bool loadParameters (const ros::NodeHandle n)
void makeHandMarker ()
 Create the interactive marker on the JACO's end effector, including pose controls and menus.
void sendStopCommand ()
 Send a 0 velocity command to the robot's arm.

Private Attributes

actionlib::SimpleActionClient
< rail_manipulation_msgs::GripperAction > 
acGripper
actionlib::SimpleActionClient
< wpi_jaco_msgs::HomeArmAction > 
acHome
actionlib::SimpleActionClient
< rail_manipulation_msgs::LiftAction > 
acLift
std::string arm_name_
ros::Publisher cartesianCmd
ros::ServiceClient eraseTrajectoriesClient
boost::shared_ptr
< interactive_markers::InteractiveMarkerServer
imServer
 interactive marker server
ros::ServiceClient jacoFkClient
 forward kinematics
std::vector< float > joints
 current joint state
ros::Subscriber jointStateSubscriber
bool lockPose
 flag to stop the arm from updating on pose changes, this is used to prevent the slight movement when left clicking on the center of the marker
interactive_markers::MenuHandler menuHandler
 interactive marker menu handler
ros::NodeHandle n
ros::ServiceClient qeClient
 rotation representation conversion client

Detailed Description

Definition at line 39 of file jaco_interactive_manipulation.h.


Constructor & Destructor Documentation

Constructor.

Definition at line 5 of file jaco_interactive_manipulation.cpp.


Member Function Documentation

Todo:
MdL [IMPR]: Return is values are all correctly loaded.

Definition at line 317 of file jaco_interactive_manipulation.cpp.

Create the interactive marker on the JACO's end effector, including pose controls and menus.

Definition at line 49 of file jaco_interactive_manipulation.cpp.

void JacoInteractiveManipulation::processHandMarkerFeedback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback)

Process feedback for the interactive marker on the JACO's end effector.

Parameters:
feedbackinteractive marker feedback

Definition at line 155 of file jaco_interactive_manipulation.cpp.

Send a 0 velocity command to the robot's arm.

Definition at line 276 of file jaco_interactive_manipulation.cpp.

void JacoInteractiveManipulation::updateJoints ( const sensor_msgs::JointState::ConstPtr &  msg)

Callback for the joint state listener.

Parameters:
msgnew joint state message

Definition at line 41 of file jaco_interactive_manipulation.cpp.

Update the interactive marker on the JACO's end effector to move based on the the current joint state of the arm.

Definition at line 298 of file jaco_interactive_manipulation.cpp.


Member Data Documentation

actionlib::SimpleActionClient<rail_manipulation_msgs::GripperAction> JacoInteractiveManipulation::acGripper [private]

Definition at line 92 of file jaco_interactive_manipulation.h.

actionlib::SimpleActionClient<wpi_jaco_msgs::HomeArmAction> JacoInteractiveManipulation::acHome [private]

Definition at line 94 of file jaco_interactive_manipulation.h.

actionlib::SimpleActionClient<rail_manipulation_msgs::LiftAction> JacoInteractiveManipulation::acLift [private]

Definition at line 93 of file jaco_interactive_manipulation.h.

Definition at line 100 of file jaco_interactive_manipulation.h.

Definition at line 83 of file jaco_interactive_manipulation.h.

Definition at line 87 of file jaco_interactive_manipulation.h.

interactive marker server

Definition at line 96 of file jaco_interactive_manipulation.h.

forward kinematics

Definition at line 88 of file jaco_interactive_manipulation.h.

std::vector<float> JacoInteractiveManipulation::joints [private]

current joint state

Definition at line 98 of file jaco_interactive_manipulation.h.

Definition at line 84 of file jaco_interactive_manipulation.h.

flag to stop the arm from updating on pose changes, this is used to prevent the slight movement when left clicking on the center of the marker

Definition at line 99 of file jaco_interactive_manipulation.h.

interactive marker menu handler

Definition at line 97 of file jaco_interactive_manipulation.h.

Definition at line 80 of file jaco_interactive_manipulation.h.

rotation representation conversion client

Definition at line 89 of file jaco_interactive_manipulation.h.


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


jaco_interaction
Author(s): David Kent
autogenerated on Thu Jun 6 2019 19:43:26