#include <interactive_frame_target.h>
Public Member Functions | |
bool | initialize () |
InteractiveFrameTarget () | |
~InteractiveFrameTarget () | |
Public Attributes | |
ros::NodeHandle | nh_ |
tf::TransformBroadcaster | tf_broadcaster_ |
tf::TransformListener | tf_listener_ |
Private Member Functions | |
void | markerFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
void | menuFeedback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
void | sendTransform (const ros::TimerEvent &event) |
void | startLookat (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
void | startTracking (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
void | stop (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
void | updateMarker (const std::string &frame) |
Private Attributes | |
std::string | chain_tip_link_ |
interactive_markers::InteractiveMarkerServer * | ia_server_ |
visualization_msgs::InteractiveMarker | int_marker_ |
visualization_msgs::InteractiveMarker | int_marker_menu_ |
bool | lookat_ |
interactive_markers::MenuHandler | menu_handler_ |
bool | movable_rot_ |
bool | movable_trans_ |
boost::mutex | mutex_ |
std::string | root_frame_ |
ros::ServiceClient | start_lookat_client_ |
ros::ServiceClient | start_tracking_client_ |
ros::ServiceClient | stop_client_ |
std::string | target_frame_ |
tf::StampedTransform | target_pose_ |
ros::Timer | timer_ |
bool | tracking_ |
std::string | tracking_frame_ |
double | update_rate_ |
Definition at line 37 of file interactive_frame_target.h.
InteractiveFrameTarget::InteractiveFrameTarget | ( | ) | [inline] |
Definition at line 40 of file interactive_frame_target.h.
InteractiveFrameTarget::~InteractiveFrameTarget | ( | ) | [inline] |
Definition at line 41 of file interactive_frame_target.h.
bool InteractiveFrameTarget::initialize | ( | ) |
void InteractiveFrameTarget::markerFeedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 323 of file interactive_frame_target.cpp.
void InteractiveFrameTarget::menuFeedback | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 318 of file interactive_frame_target.cpp.
void InteractiveFrameTarget::sendTransform | ( | const ros::TimerEvent & | event | ) | [private] |
Definition at line 223 of file interactive_frame_target.cpp.
void InteractiveFrameTarget::startLookat | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 280 of file interactive_frame_target.cpp.
void InteractiveFrameTarget::startTracking | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 262 of file interactive_frame_target.cpp.
void InteractiveFrameTarget::stop | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [private] |
Definition at line 301 of file interactive_frame_target.cpp.
void InteractiveFrameTarget::updateMarker | ( | const std::string & | frame | ) | [private] |
Definition at line 233 of file interactive_frame_target.cpp.
std::string InteractiveFrameTarget::chain_tip_link_ [private] |
Definition at line 54 of file interactive_frame_target.h.
Definition at line 61 of file interactive_frame_target.h.
visualization_msgs::InteractiveMarker InteractiveFrameTarget::int_marker_ [private] |
Definition at line 62 of file interactive_frame_target.h.
visualization_msgs::InteractiveMarker InteractiveFrameTarget::int_marker_menu_ [private] |
Definition at line 63 of file interactive_frame_target.h.
bool InteractiveFrameTarget::lookat_ [private] |
Definition at line 67 of file interactive_frame_target.h.
Definition at line 64 of file interactive_frame_target.h.
bool InteractiveFrameTarget::movable_rot_ [private] |
Definition at line 59 of file interactive_frame_target.h.
bool InteractiveFrameTarget::movable_trans_ [private] |
Definition at line 58 of file interactive_frame_target.h.
boost::mutex InteractiveFrameTarget::mutex_ [private] |
Definition at line 69 of file interactive_frame_target.h.
Definition at line 45 of file interactive_frame_target.h.
std::string InteractiveFrameTarget::root_frame_ [private] |
Definition at line 53 of file interactive_frame_target.h.
Definition at line 72 of file interactive_frame_target.h.
Definition at line 71 of file interactive_frame_target.h.
Definition at line 73 of file interactive_frame_target.h.
std::string InteractiveFrameTarget::target_frame_ [private] |
Definition at line 56 of file interactive_frame_target.h.
Definition at line 68 of file interactive_frame_target.h.
Definition at line 47 of file interactive_frame_target.h.
Definition at line 46 of file interactive_frame_target.h.
ros::Timer InteractiveFrameTarget::timer_ [private] |
Definition at line 50 of file interactive_frame_target.h.
bool InteractiveFrameTarget::tracking_ [private] |
Definition at line 66 of file interactive_frame_target.h.
std::string InteractiveFrameTarget::tracking_frame_ [private] |
Definition at line 55 of file interactive_frame_target.h.
double InteractiveFrameTarget::update_rate_ [private] |
Definition at line 51 of file interactive_frame_target.h.