IRI ROS Specific Driver Class. More...
#include <wam_actions.h>
Public Member Functions | |
bool | drop () |
bool | drop (double x, double y, double z) |
bool | flip () |
bool | fold () |
bool | fromAtoB () |
bool | fromBtoA () |
bool | isograsp () |
void | mainLoop (void) |
main node thread | |
bool | peggrasp () |
bool | requestGraspingPoint (double &x, double &y, double &z, int zone=ANYZONE, int filterID=ALLFILTERS) |
bool | requestGraspingPointMaxHeight (double &x, double &y, double &z, int zone=ANYZONE, int filterID=ALLFILTERS) |
bool | shake () |
bool | stretch () |
bool | take3D (double x, double y, double z) |
bool | take3Dside (double x, double y, double z) |
WamActions () | |
constructor | |
Private Member Functions | |
bool | check_box (double x, double y, double z) |
bool | fit_box (double &x, double &y, double &z) |
void | get_destination (int destination_zone, double &x, double &y, double &z) |
bool | go_to (double x, double y, double z) |
bool | go_to_kinect () |
bool | wam_actionCallback (iri_wam_common_msgs::wamaction::Request &req, iri_wam_common_msgs::wamaction::Response &res) |
Private Attributes | |
ros::ServiceClient | barrett_hand_cmd_client |
iri_wam_common_msgs::bhand_cmd | barrett_hand_cmd_srv |
int | destination_counter |
ros::NodeHandle | node_handle_ |
ros::ServiceClient | obj_filter_client |
iri_wam_common_msgs::compute_obj_grasp_pose | obj_filter_srv |
ros::ServiceClient | pose_move_client |
iri_wam_common_msgs::pose_move | pose_move_srv |
geometry_msgs::Pose | sampleposes [NUMPOSES] |
tf::TransformBroadcaster | tf_br |
CMutex | tf_broadcaster_mutex |
tf::TransformListener | tf_grasp |
tf::Transform | transform_grasping_point |
std::string | wam0_ |
ros::ServiceServer | wam_action_server |
IRI ROS Specific Driver Class.
IMPORTANT NOTE: This code has been generated through a script from the iri_ros_scripts. Please do NOT delete any comments to guarantee the correctness of the scripts. ROS topics can be easly add by using those scripts. Please refer to the IRI Wiki page for more information: http://wikiri.upc.es/index.php/Robotics_Lab
This class inherits from the IRI Base class CIriNode<CIriDriver>, to provide an execution thread to the driver object. A complete framework with utilites to test the node functionallity or to add diagnostics to specific situations is also given. The inherit template design form allows complete access to any CIriDriver object implementation.
As mentioned, tests in the different driver states can be performed through class methods such as addNodeOpenedTests() or addNodeRunningTests(). Tests common to all nodes may be also executed in the pattern class CIriNode. Similarly to the tests, diagnostics can easyly be added. See ROS Wiki for more details: http://www.ros.org/wiki/diagnostics/ (Tutorials: Creating a Diagnostic Analyzer) http://www.ros.org/wiki/self_test/ (Example: Self Test)
Definition at line 87 of file wam_actions.h.
constructor
This constructor mainly creates and initializes the WamActions topics through the given NodeHandle object. CIriNode attributes may be also modified to suit node specifications.
All kind of ROS topics (publishers, subscribers, servers or clients) can be easyly generated with the scripts in the iri_ros_scripts package. Refer to ROS and IRI Wiki pages for more details:
http://www.ros.org/wiki/ROS/Tutorials/WritingPublisherSubscriber(c++) http://www.ros.org/wiki/ROS/Tutorials/WritingServiceClient(c++) http://wikiri.upc.es/index.php/Robotics_Lab
nh | a reference to the node handle object to manage all ROS topics. |
Definition at line 5 of file wam_actions.cpp.
bool WamActions::check_box | ( | double | x, |
double | y, | ||
double | z | ||
) | [private] |
Definition at line 304 of file wam_actions.cpp.
bool WamActions::drop | ( | ) |
Definition at line 569 of file wam_actions.cpp.
bool WamActions::drop | ( | double | x, |
double | y, | ||
double | z | ||
) |
Definition at line 581 of file wam_actions.cpp.
bool WamActions::fit_box | ( | double & | x, |
double & | y, | ||
double & | z | ||
) | [private] |
Definition at line 308 of file wam_actions.cpp.
bool WamActions::flip | ( | ) |
Definition at line 611 of file wam_actions.cpp.
bool WamActions::fold | ( | ) |
Definition at line 606 of file wam_actions.cpp.
void WamActions::get_destination | ( | int | destination_zone, |
double & | x, | ||
double & | y, | ||
double & | z | ||
) | [private] |
Definition at line 616 of file wam_actions.cpp.
bool WamActions::go_to | ( | double | x, |
double | y, | ||
double | z | ||
) | [private] |
Definition at line 327 of file wam_actions.cpp.
bool WamActions::go_to_kinect | ( | ) | [private] |
Definition at line 352 of file wam_actions.cpp.
void WamActions::mainLoop | ( | void | ) |
main node thread
This is the main thread node function. Code written here will be executed in every node loop while the driver is on running state. Loop frequency can be tuned my modifying loop_rate attribute.
Here data related to the process loop or to ROS topics (mainly data structs related to the MSG and SRV files) must be updated. ROS publisher objects must publish their data in this process. ROS client servers may also request data to the corresponding server topics.
Definition at line 33 of file wam_actions.cpp.
bool WamActions::requestGraspingPoint | ( | double & | x, |
double & | y, | ||
double & | z, | ||
int | zone = ANYZONE , |
||
int | filterID = ALLFILTERS |
||
) |
Definition at line 374 of file wam_actions.cpp.
bool WamActions::requestGraspingPointMaxHeight | ( | double & | x, |
double & | y, | ||
double & | z, | ||
int | zone = ANYZONE , |
||
int | filterID = ALLFILTERS |
||
) |
Definition at line 426 of file wam_actions.cpp.
bool WamActions::take3D | ( | double | x, |
double | y, | ||
double | z | ||
) |
Definition at line 523 of file wam_actions.cpp.
bool WamActions::take3Dside | ( | double | x, |
double | y, | ||
double | z | ||
) |
Definition at line 477 of file wam_actions.cpp.
bool WamActions::wam_actionCallback | ( | iri_wam_common_msgs::wamaction::Request & | req, |
iri_wam_common_msgs::wamaction::Response & | res | ||
) | [private] |
Definition at line 58 of file wam_actions.cpp.
Definition at line 110 of file wam_actions.h.
iri_wam_common_msgs::bhand_cmd WamActions::barrett_hand_cmd_srv [private] |
Definition at line 111 of file wam_actions.h.
int WamActions::destination_counter [private] |
Definition at line 123 of file wam_actions.h.
ros::NodeHandle WamActions::node_handle_ [private] |
Definition at line 91 of file wam_actions.h.
Definition at line 108 of file wam_actions.h.
iri_wam_common_msgs::compute_obj_grasp_pose WamActions::obj_filter_srv [private] |
Definition at line 109 of file wam_actions.h.
Definition at line 112 of file wam_actions.h.
iri_wam_common_msgs::pose_move WamActions::pose_move_srv [private] |
Definition at line 113 of file wam_actions.h.
geometry_msgs::Pose WamActions::sampleposes[NUMPOSES] [private] |
Definition at line 92 of file wam_actions.h.
tf::TransformBroadcaster WamActions::tf_br [private] |
Definition at line 93 of file wam_actions.h.
CMutex WamActions::tf_broadcaster_mutex [private] |
Definition at line 90 of file wam_actions.h.
tf::TransformListener WamActions::tf_grasp [private] |
Definition at line 94 of file wam_actions.h.
Definition at line 99 of file wam_actions.h.
std::string WamActions::wam0_ [private] |
Definition at line 96 of file wam_actions.h.
Definition at line 104 of file wam_actions.h.