#include <unlatching.h>
Public Member Functions | |
void | addTrajectoryPoint (ee_cart_imped_msgs::EECartImpedGoal &msg, tf::Transform pose, float fx, float fy, float fz, float tx, float ty, float tz, float time, std::string frame_id) |
DoorOpener (unsigned char side= 'r') | |
void | drive_base (const ros::TimerEvent &event) |
Sends the command to drive the base. Needs to be called periodically. | |
void | grasp_handle (const boost::shared_ptr< const geometry_msgs::PoseStamped_< std::allocator< void > > > a_pregrasp, const boost::shared_ptr< const geometry_msgs::PoseStamped_< std::allocator< void > > > a_grasp, const boost::shared_ptr< const geometry_msgs::PoseStamped_< std::allocator< void > > > a_postgrasp) |
void | home_position () |
Gripper to front of robot. | |
bool | listen (std_srvs::Empty::Request &, std_srvs::Empty::Response &) |
bool | swing_door (geometry_msgs::PoseStamped) |
void | use_gripper (float position, float effort) |
Open or close gripper. | |
bool | wait_for_gripper () |
~DoorOpener () | |
Private Member Functions | |
tf::StampedTransform | getTransform (const std::string &from, const std::string &to) |
void | push_door () |
void | withdraw (float meters) |
Private Attributes | |
EECartImpedArm * | arm_ |
geometry_msgs::Twist | base_cmd |
ros::Publisher | cmd_vel_pub_ |
std::string | fixed_frame_name_ |
message_filters::Subscriber < geometry_msgs::PoseStamped > | grasp_sub |
gripActClient * | gripperClient |
bool | listening_ |
ros::NodeHandle | n |
message_filters::Subscriber < geometry_msgs::PoseStamped > | postgrasp_sub |
message_filters::Subscriber < geometry_msgs::PoseStamped > | pregrasp_sub |
ros::ServiceServer | serviceServer |
unsigned char | side_ |
bool | started_ |
bool | success_ |
message_filters::Synchronizer < MySyncPolicy > | sync |
tf::TransformListener * | tflistener_ |
std::string | tool_frame_name_ |
Definition at line 25 of file unlatching.h.
DoorOpener::DoorOpener | ( | unsigned char | side = 'r' | ) |
Definition at line 8 of file unlatching.cpp.
Definition at line 55 of file unlatching.cpp.
void DoorOpener::addTrajectoryPoint | ( | ee_cart_imped_msgs::EECartImpedGoal & | msg, |
tf::Transform | pose, | ||
float | fx, | ||
float | fy, | ||
float | fz, | ||
float | tx, | ||
float | ty, | ||
float | tz, | ||
float | time, | ||
std::string | frame_id | ||
) |
Definition at line 351 of file unlatching.cpp.
void DoorOpener::drive_base | ( | const ros::TimerEvent & | event | ) |
Sends the command to drive the base. Needs to be called periodically.
Definition at line 110 of file unlatching.cpp.
tf::StampedTransform DoorOpener::getTransform | ( | const std::string & | from, |
const std::string & | to | ||
) | [private] |
Definition at line 341 of file unlatching.cpp.
void DoorOpener::grasp_handle | ( | const boost::shared_ptr< const geometry_msgs::PoseStamped_< std::allocator< void > > > | a_pregrasp, |
const boost::shared_ptr< const geometry_msgs::PoseStamped_< std::allocator< void > > > | a_grasp, | ||
const boost::shared_ptr< const geometry_msgs::PoseStamped_< std::allocator< void > > > | a_postgrasp | ||
) |
Definition at line 223 of file unlatching.cpp.
void DoorOpener::home_position | ( | ) |
Gripper to front of robot.
Definition at line 184 of file unlatching.cpp.
bool DoorOpener::listen | ( | std_srvs::Empty::Request & | , |
std_srvs::Empty::Response & | |||
) |
Definition at line 39 of file unlatching.cpp.
void DoorOpener::push_door | ( | ) | [private] |
Definition at line 118 of file unlatching.cpp.
bool DoorOpener::swing_door | ( | geometry_msgs::PoseStamped | start_pose | ) |
Definition at line 364 of file unlatching.cpp.
void DoorOpener::use_gripper | ( | float | position, |
float | effort | ||
) |
Open or close gripper.
Definition at line 61 of file unlatching.cpp.
Definition at line 72 of file unlatching.cpp.
void DoorOpener::withdraw | ( | float | meters | ) | [private] |
Retreat the gripper along its x-axis. meters gives the length to withdraw in meters
Definition at line 198 of file unlatching.cpp.
EECartImpedArm* DoorOpener::arm_ [private] |
Definition at line 56 of file unlatching.h.
geometry_msgs::Twist DoorOpener::base_cmd [private] |
Definition at line 54 of file unlatching.h.
ros::Publisher DoorOpener::cmd_vel_pub_ [private] |
Definition at line 53 of file unlatching.h.
std::string DoorOpener::fixed_frame_name_ [private] |
Definition at line 59 of file unlatching.h.
message_filters::Subscriber<geometry_msgs::PoseStamped> DoorOpener::grasp_sub [private] |
Definition at line 50 of file unlatching.h.
gripActClient* DoorOpener::gripperClient [private] |
Definition at line 46 of file unlatching.h.
bool DoorOpener::listening_ [private] |
Definition at line 65 of file unlatching.h.
ros::NodeHandle DoorOpener::n [private] |
Definition at line 47 of file unlatching.h.
message_filters::Subscriber<geometry_msgs::PoseStamped> DoorOpener::postgrasp_sub [private] |
Definition at line 51 of file unlatching.h.
message_filters::Subscriber<geometry_msgs::PoseStamped> DoorOpener::pregrasp_sub [private] |
Definition at line 49 of file unlatching.h.
ros::ServiceServer DoorOpener::serviceServer [private] |
Definition at line 48 of file unlatching.h.
unsigned char DoorOpener::side_ [private] |
Definition at line 55 of file unlatching.h.
bool DoorOpener::started_ [private] |
Definition at line 66 of file unlatching.h.
bool DoorOpener::success_ [private] |
Definition at line 67 of file unlatching.h.
Definition at line 52 of file unlatching.h.
tf::TransformListener* DoorOpener::tflistener_ [private] |
Definition at line 57 of file unlatching.h.
std::string DoorOpener::tool_frame_name_ [private] |
Definition at line 58 of file unlatching.h.