Public Member Functions | |
| ArmMarkerServer () | |
| void | changeMarkerColor (double r, double g, double b, bool set_pose=false, geometry_msgs::Pose pose=geometry_msgs::Pose()) |
| void | createArmMarker () |
| void | createArmMenu () |
| void | createGripperMarker () |
| void | createJointMarker (const string joint_name, const string link_name) |
| void | createJointMarkers () |
| void | createJointMenu (const string joint_name) |
| void | createJointMenus () |
| void | createJointPublishers () |
| void | getTransformedPose (const string &source_frame, const geometry_msgs::Pose &source_pose, const string &target_frame, geometry_msgs::Pose &target_pose, const ros::Time &time) |
| void | immediateCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | processArmFeedback (const InteractiveMarkerFeedbackConstPtr &feedback) |
| void | processCommand (const actionlib::SimpleClientGoalState &state, const simple_arm_server::MoveArmResultConstPtr &result, const InteractiveMarkerFeedbackConstPtr &feedback) |
| void | processJointFeedback (const InteractiveMarkerFeedbackConstPtr &feedback) |
| void | relaxAllCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | relaxCb (const std::string joint_name, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | resetMarker () |
| void | resetPoseCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | sendCommandCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| bool | sendGripperCommand (const InteractiveMarkerFeedbackConstPtr &feedback) |
| bool | sendTrajectoryCommand (const InteractiveMarkerFeedbackConstPtr &feedback) |
| void | switchToArmControlCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
| void | switchToJointControlCb (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
Private Attributes | |
| MenuHandler | arm_menu_handler |
| ros::Timer | arm_timer |
| actionlib::SimpleActionClient < simple_arm_server::MoveArmAction > | client |
| double | gripper_box_offset_x |
| double | gripper_box_offset_y |
| double | gripper_box_offset_z |
| double | gripper_marker_offset_x |
| double | gripper_marker_offset_y |
| double | gripper_marker_offset_z |
| bool | immediate_commands |
| bool | in_move |
| map< std::string, ros::Publisher > | joint_command_publishers |
| map< std::string, MenuHandler > | joint_menu_handlers |
| map< std::string, ros::ServiceClient > | joint_relax_clients |
| vector< string > | joints |
| vector< string > | links |
| double | move_time |
| ros::NodeHandle | nh |
| string | root_link |
| interactive_markers::InteractiveMarkerServer | server |
| tf::TransformListener | tf_listener |
| string | tip_link |
Definition at line 54 of file arm_marker_server.cpp.
| ArmMarkerServer::ArmMarkerServer | ( | ) | [inline] |
Definition at line 93 of file arm_marker_server.cpp.
| void ArmMarkerServer::changeMarkerColor | ( | double | r, |
| double | g, | ||
| double | b, | ||
| bool | set_pose = false, |
||
| geometry_msgs::Pose | pose = geometry_msgs::Pose() |
||
| ) | [inline] |
Definition at line 175 of file arm_marker_server.cpp.
| void ArmMarkerServer::createArmMarker | ( | ) | [inline] |
Definition at line 296 of file arm_marker_server.cpp.
| void ArmMarkerServer::createArmMenu | ( | ) | [inline] |
Definition at line 440 of file arm_marker_server.cpp.
| void ArmMarkerServer::createGripperMarker | ( | ) | [inline] |
Definition at line 362 of file arm_marker_server.cpp.
| void ArmMarkerServer::createJointMarker | ( | const string | joint_name, |
| const string | link_name | ||
| ) | [inline] |
Definition at line 418 of file arm_marker_server.cpp.
| void ArmMarkerServer::createJointMarkers | ( | ) | [inline] |
Definition at line 410 of file arm_marker_server.cpp.
| void ArmMarkerServer::createJointMenu | ( | const string | joint_name | ) | [inline] |
Definition at line 469 of file arm_marker_server.cpp.
| void ArmMarkerServer::createJointMenus | ( | ) | [inline] |
Definition at line 461 of file arm_marker_server.cpp.
| void ArmMarkerServer::createJointPublishers | ( | ) | [inline] |
Definition at line 143 of file arm_marker_server.cpp.
| void ArmMarkerServer::getTransformedPose | ( | const string & | source_frame, |
| const geometry_msgs::Pose & | source_pose, | ||
| const string & | target_frame, | ||
| geometry_msgs::Pose & | target_pose, | ||
| const ros::Time & | time | ||
| ) | [inline] |
Definition at line 254 of file arm_marker_server.cpp.
| void ArmMarkerServer::immediateCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 501 of file arm_marker_server.cpp.
| void ArmMarkerServer::processArmFeedback | ( | const InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 153 of file arm_marker_server.cpp.
| void ArmMarkerServer::processCommand | ( | const actionlib::SimpleClientGoalState & | state, |
| const simple_arm_server::MoveArmResultConstPtr & | result, | ||
| const InteractiveMarkerFeedbackConstPtr & | feedback | ||
| ) | [inline] |
Definition at line 193 of file arm_marker_server.cpp.
| void ArmMarkerServer::processJointFeedback | ( | const InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 168 of file arm_marker_server.cpp.
| void ArmMarkerServer::relaxAllCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 487 of file arm_marker_server.cpp.
| void ArmMarkerServer::relaxCb | ( | const std::string | joint_name, |
| const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ||
| ) | [inline] |
Definition at line 495 of file arm_marker_server.cpp.
| void ArmMarkerServer::resetMarker | ( | ) | [inline] |
Definition at line 284 of file arm_marker_server.cpp.
| void ArmMarkerServer::resetPoseCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 524 of file arm_marker_server.cpp.
| void ArmMarkerServer::sendCommandCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 482 of file arm_marker_server.cpp.
| bool ArmMarkerServer::sendGripperCommand | ( | const InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 234 of file arm_marker_server.cpp.
| bool ArmMarkerServer::sendTrajectoryCommand | ( | const InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 213 of file arm_marker_server.cpp.
| void ArmMarkerServer::switchToArmControlCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 539 of file arm_marker_server.cpp.
| void ArmMarkerServer::switchToJointControlCb | ( | const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ) | [inline] |
Definition at line 530 of file arm_marker_server.cpp.
MenuHandler ArmMarkerServer::arm_menu_handler [private] |
Definition at line 62 of file arm_marker_server.cpp.
ros::Timer ArmMarkerServer::arm_timer [private] |
Definition at line 68 of file arm_marker_server.cpp.
Definition at line 58 of file arm_marker_server.cpp.
double ArmMarkerServer::gripper_box_offset_x [private] |
Definition at line 81 of file arm_marker_server.cpp.
double ArmMarkerServer::gripper_box_offset_y [private] |
Definition at line 82 of file arm_marker_server.cpp.
double ArmMarkerServer::gripper_box_offset_z [private] |
Definition at line 83 of file arm_marker_server.cpp.
double ArmMarkerServer::gripper_marker_offset_x [private] |
Definition at line 77 of file arm_marker_server.cpp.
double ArmMarkerServer::gripper_marker_offset_y [private] |
Definition at line 78 of file arm_marker_server.cpp.
double ArmMarkerServer::gripper_marker_offset_z [private] |
Definition at line 79 of file arm_marker_server.cpp.
bool ArmMarkerServer::immediate_commands [private] |
Definition at line 65 of file arm_marker_server.cpp.
bool ArmMarkerServer::in_move [private] |
Definition at line 66 of file arm_marker_server.cpp.
map<std::string, ros::Publisher> ArmMarkerServer::joint_command_publishers [private] |
Definition at line 89 of file arm_marker_server.cpp.
map<std::string, MenuHandler> ArmMarkerServer::joint_menu_handlers [private] |
Definition at line 63 of file arm_marker_server.cpp.
map<std::string, ros::ServiceClient> ArmMarkerServer::joint_relax_clients [private] |
Definition at line 90 of file arm_marker_server.cpp.
vector<string> ArmMarkerServer::joints [private] |
Definition at line 71 of file arm_marker_server.cpp.
vector<string> ArmMarkerServer::links [private] |
Definition at line 72 of file arm_marker_server.cpp.
double ArmMarkerServer::move_time [private] |
Definition at line 86 of file arm_marker_server.cpp.
ros::NodeHandle ArmMarkerServer::nh [private] |
Definition at line 57 of file arm_marker_server.cpp.
string ArmMarkerServer::root_link [private] |
Definition at line 74 of file arm_marker_server.cpp.
Definition at line 59 of file arm_marker_server.cpp.
Definition at line 60 of file arm_marker_server.cpp.
string ArmMarkerServer::tip_link [private] |
Definition at line 73 of file arm_marker_server.cpp.