Provides manipulation actions for the JACO arm. More...
#include <jaco_manipulation.h>
Public Types | |
typedef actionlib::SimpleActionClient < control_msgs::GripperCommandAction > | GripperClient |
typedef actionlib::SimpleActionServer < rail_manipulation_msgs::GripperAction > | GripperServer |
typedef actionlib::SimpleActionServer < rail_manipulation_msgs::LiftAction > | LiftServer |
Public Member Functions | |
void | execute_gripper (const rail_manipulation_msgs::GripperGoalConstPtr &goal) |
Callback for the executeGraspServer, closes the gripper until an object is grasped, alternatively opens the gripper fully. | |
void | execute_lift (const rail_manipulation_msgs::LiftGoalConstPtr &goal) |
Callback for the executePickupServer, lifts the arm while applying input to keep the gripper closed. | |
JacoManipulation () | |
Constructor. | |
void | jointStateCallback (const sensor_msgs::JointState msg) |
Callback for joint state updates. | |
Private Member Functions | |
bool | loadParameters (const ros::NodeHandle n) |
Private Attributes | |
GripperClient * | acGripper |
ros::Publisher | angularCmdPublisher |
std::string | arm_name_ |
GripperServer * | asGripper |
LiftServer * | asLift |
ros::Publisher | cartesianCmdPublisher |
ros::ServiceClient | cartesianPositionClient |
ros::ServiceClient | eraseTrajectoriesClient |
double | gripper_closed_ |
double | gripper_open_ |
std::vector< double > | joint_pos_ |
ros::Subscriber | jointStateSubscriber |
bool | kinova_gripper_ |
ros::NodeHandle | n |
int | num_fingers_ |
int | num_joints_ |
ros::NodeHandle | pnh |
std::string | topic_prefix_ |
Provides manipulation actions for the JACO arm.
JacoManipulation creates a ROS node that provides action servers for executing manipulation actions including grasping, releasing, and object pickup.
Definition at line 42 of file jaco_manipulation.h.
typedef actionlib::SimpleActionClient<control_msgs::GripperCommandAction> JacoManipulation::GripperClient |
Definition at line 45 of file jaco_manipulation.h.
typedef actionlib::SimpleActionServer<rail_manipulation_msgs::GripperAction> JacoManipulation::GripperServer |
Definition at line 46 of file jaco_manipulation.h.
typedef actionlib::SimpleActionServer<rail_manipulation_msgs::LiftAction> JacoManipulation::LiftServer |
Definition at line 47 of file jaco_manipulation.h.
Constructor.
Definition at line 5 of file jaco_manipulation.cpp.
void JacoManipulation::execute_gripper | ( | const rail_manipulation_msgs::GripperGoalConstPtr & | goal | ) |
Callback for the executeGraspServer, closes the gripper until an object is grasped, alternatively opens the gripper fully.
goal | action goal |
Definition at line 76 of file jaco_manipulation.cpp.
void JacoManipulation::execute_lift | ( | const rail_manipulation_msgs::LiftGoalConstPtr & | goal | ) |
Callback for the executePickupServer, lifts the arm while applying input to keep the gripper closed.
goal | action goal |
Definition at line 152 of file jaco_manipulation.cpp.
void JacoManipulation::jointStateCallback | ( | const sensor_msgs::JointState | msg | ) |
Callback for joint state updates.
msg | joint state message |
Definition at line 70 of file jaco_manipulation.cpp.
bool JacoManipulation::loadParameters | ( | const ros::NodeHandle | n | ) | [private] |
Definition at line 40 of file jaco_manipulation.cpp.
GripperClient* JacoManipulation::acGripper [private] |
Definition at line 95 of file jaco_manipulation.h.
Definition at line 87 of file jaco_manipulation.h.
std::string JacoManipulation::arm_name_ [private] |
Definition at line 77 of file jaco_manipulation.h.
GripperServer* JacoManipulation::asGripper [private] |
Definition at line 96 of file jaco_manipulation.h.
LiftServer* JacoManipulation::asLift [private] |
Definition at line 97 of file jaco_manipulation.h.
Definition at line 86 of file jaco_manipulation.h.
Definition at line 91 of file jaco_manipulation.h.
Definition at line 92 of file jaco_manipulation.h.
double JacoManipulation::gripper_closed_ [private] |
Definition at line 79 of file jaco_manipulation.h.
double JacoManipulation::gripper_open_ [private] |
Definition at line 80 of file jaco_manipulation.h.
std::vector<double> JacoManipulation::joint_pos_ [private] |
Definition at line 99 of file jaco_manipulation.h.
Definition at line 88 of file jaco_manipulation.h.
bool JacoManipulation::kinova_gripper_ [private] |
Definition at line 83 of file jaco_manipulation.h.
ros::NodeHandle JacoManipulation::n [private] |
Definition at line 74 of file jaco_manipulation.h.
int JacoManipulation::num_fingers_ [private] |
Definition at line 81 of file jaco_manipulation.h.
int JacoManipulation::num_joints_ [private] |
Definition at line 82 of file jaco_manipulation.h.
ros::NodeHandle JacoManipulation::pnh [private] |
Definition at line 74 of file jaco_manipulation.h.
std::string JacoManipulation::topic_prefix_ [private] |
Definition at line 78 of file jaco_manipulation.h.