#include <interactive_robot.h>
Classes | |
class | RobotLoadException |
Public Member Functions | |
const std::string & | getGroupName () const |
void | getWorldGeometry (Eigen::Affine3d &pose, double &size) |
InteractiveRobot (const std::string &robot_description="robot_description", const std::string &robot_topic="interactive_robot_state", const std::string &marker_topic="interactive_robot_markers", const std::string &imarker_topic="interactive_robot_imarkers") | |
robot_model::RobotModelPtr & | robotModel () |
robot_state::RobotStatePtr & | robotState () |
void | setGroup (const std::string &name) |
bool | setGroupPose (const Eigen::Affine3d &pose) |
void | setUserCallback (boost::function< void(InteractiveRobot &robot)> callback) |
void | setWorldObjectPose (const Eigen::Affine3d &pose) |
~InteractiveRobot () | |
Public Attributes | |
void * | user_data_ |
Private Member Functions | |
void | publishRobotState () |
void | publishWorldState () |
void | scheduleUpdate () |
bool | setCallbackTimer (bool new_update_request) |
void | updateAll () |
void | updateCallback (const ros::TimerEvent &e) |
Static Private Member Functions | |
static void | movedRobotMarkerCallback (InteractiveRobot *robot, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
static void | movedWorldMarkerCallback (InteractiveRobot *robot, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback) |
Private Attributes | |
ros::Duration | average_callback_duration_ |
Eigen::Affine3d | desired_group_end_link_pose_ |
Eigen::Affine3d | desired_world_object_pose_ |
robot_state::JointStateGroup * | group_ |
IMarker * | imarker_robot_ |
IMarker * | imarker_world_ |
ros::Time | init_time_ |
interactive_markers::InteractiveMarkerServer | interactive_marker_server_ |
ros::Time | last_callback_time_ |
ros::NodeHandle | nh_ |
ros::Timer | publish_timer_ |
robot_model_loader::RobotModelLoader | rm_loader_ |
robot_model::RobotModelPtr | robot_model_ |
robot_state::RobotStatePtr | robot_state_ |
ros::Publisher | robot_state_publisher_ |
int | schedule_request_count_ |
boost::function< void(InteractiveRobot &robot)> | user_callback_ |
ros::Publisher | world_state_publisher_ |
Static Private Attributes | |
static const Eigen::Affine3d | DEFAULT_WORLD_OBJECT_POSE_ |
static const ros::Duration | min_delay_ |
static const double | WORLD_BOX_SIZE_ = 0.15 |
Keeps track of the state of the robot and the world. Updates the state when interactive markers are manipulated. Publishes the state to rviz.
Definition at line 56 of file interactive_robot.h.
InteractiveRobot::InteractiveRobot | ( | const std::string & | robot_description = "robot_description" , |
const std::string & | robot_topic = "interactive_robot_state" , |
||
const std::string & | marker_topic = "interactive_robot_markers" , |
||
const std::string & | imarker_topic = "interactive_robot_imarkers" |
||
) |
Definition at line 57 of file interactive_robot.cpp.
Definition at line 127 of file interactive_robot.cpp.
const std::string & InteractiveRobot::getGroupName | ( | ) | const |
Definition at line 278 of file interactive_robot.cpp.
void InteractiveRobot::getWorldGeometry | ( | Eigen::Affine3d & | pose, |
double & | size | ||
) |
return size and pose of world object cube
Definition at line 329 of file interactive_robot.cpp.
void InteractiveRobot::movedRobotMarkerCallback | ( | InteractiveRobot * | robot, |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ||
) | [static, private] |
Definition at line 134 of file interactive_robot.cpp.
void InteractiveRobot::movedWorldMarkerCallback | ( | InteractiveRobot * | robot, |
const visualization_msgs::InteractiveMarkerFeedbackConstPtr & | feedback | ||
) | [static, private] |
Definition at line 144 of file interactive_robot.cpp.
void InteractiveRobot::publishRobotState | ( | ) | [private] |
Definition at line 291 of file interactive_robot.cpp.
void InteractiveRobot::publishWorldState | ( | ) | [private] |
Definition at line 307 of file interactive_robot.cpp.
robot_model::RobotModelPtr& InteractiveRobot::robotModel | ( | ) | [inline] |
access RobotModel
Definition at line 82 of file interactive_robot.h.
robot_state::RobotStatePtr& InteractiveRobot::robotState | ( | ) | [inline] |
access RobotState
Definition at line 84 of file interactive_robot.h.
void InteractiveRobot::scheduleUpdate | ( | ) | [private] |
Definition at line 216 of file interactive_robot.cpp.
bool InteractiveRobot::setCallbackTimer | ( | bool | new_update_request | ) | [private] |
Definition at line 155 of file interactive_robot.cpp.
void InteractiveRobot::setGroup | ( | const std::string & | name | ) |
set which group to manipulate
Definition at line 259 of file interactive_robot.cpp.
bool InteractiveRobot::setGroupPose | ( | const Eigen::Affine3d & | pose | ) |
Set the pose of the group we are manipulating
Definition at line 284 of file interactive_robot.cpp.
void InteractiveRobot::setUserCallback | ( | boost::function< void(InteractiveRobot &robot)> | callback | ) | [inline] |
set a callback to call when updates occur
Definition at line 76 of file interactive_robot.h.
void InteractiveRobot::setWorldObjectPose | ( | const Eigen::Affine3d & | pose | ) |
set pose of the world object
Definition at line 300 of file interactive_robot.cpp.
void InteractiveRobot::updateAll | ( | ) | [private] |
Definition at line 245 of file interactive_robot.cpp.
void InteractiveRobot::updateCallback | ( | const ros::TimerEvent & | e | ) | [private] |
Definition at line 226 of file interactive_robot.cpp.
Definition at line 155 of file interactive_robot.h.
const Eigen::Affine3d InteractiveRobot::DEFAULT_WORLD_OBJECT_POSE_ [static, private] |
Definition at line 146 of file interactive_robot.h.
Eigen::Affine3d InteractiveRobot::desired_group_end_link_pose_ [private] |
Definition at line 141 of file interactive_robot.h.
Eigen::Affine3d InteractiveRobot::desired_world_object_pose_ [private] |
Definition at line 144 of file interactive_robot.h.
Definition at line 140 of file interactive_robot.h.
IMarker* InteractiveRobot::imarker_robot_ [private] |
Definition at line 131 of file interactive_robot.h.
IMarker* InteractiveRobot::imarker_world_ [private] |
Definition at line 132 of file interactive_robot.h.
ros::Time InteractiveRobot::init_time_ [private] |
Definition at line 153 of file interactive_robot.h.
Definition at line 130 of file interactive_robot.h.
Definition at line 154 of file interactive_robot.h.
const ros::Duration InteractiveRobot::min_delay_ [static, private] |
Definition at line 156 of file interactive_robot.h.
ros::NodeHandle InteractiveRobot::nh_ [private] |
Definition at line 127 of file interactive_robot.h.
ros::Timer InteractiveRobot::publish_timer_ [private] |
Definition at line 152 of file interactive_robot.h.
Definition at line 135 of file interactive_robot.h.
Definition at line 136 of file interactive_robot.h.
Definition at line 137 of file interactive_robot.h.
Definition at line 128 of file interactive_robot.h.
int InteractiveRobot::schedule_request_count_ [private] |
Definition at line 157 of file interactive_robot.h.
boost::function<void (InteractiveRobot& robot)> InteractiveRobot::user_callback_ [private] |
Definition at line 149 of file interactive_robot.h.
hook for user data. Unused by the InteractiveRobot class. initialized to 0
Definition at line 95 of file interactive_robot.h.
const double InteractiveRobot::WORLD_BOX_SIZE_ = 0.15 [static, private] |
Definition at line 145 of file interactive_robot.h.
Definition at line 129 of file interactive_robot.h.