47 #include <boost/lexical_cast.hpp> 48 #include <boost/math/constants/constants.hpp> 53 #include <Eigen/Geometry> 58 const robot_state::RobotState& initial_robot_state,
61 , name_(fixName(name))
62 , planning_frame_(initial_robot_state.getRobotModel()->getModelFrame())
64 , robot_interaction_(NULL)
65 , kinematic_options_map_(robot_interaction->getKinematicOptionsMap())
66 , display_meshes_(true)
67 , display_controls_(true)
116 std::replace(name.begin(), name.end(),
'_',
'-');
177 std::map<std::string, geometry_msgs::PoseStamped>::iterator it =
pose_map_.find(eef.
eef_group);
189 std::map<std::string, geometry_msgs::PoseStamped>::iterator it =
pose_map_.find(vj.
joint_name);
235 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
251 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
253 if (feedback->event_type != visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE)
256 geometry_msgs::PoseStamped tpose;
257 geometry_msgs::Pose offset;
259 offset.orientation.w = 1;
282 const visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
284 if (feedback->event_type != visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE)
287 geometry_msgs::PoseStamped tpose;
288 geometry_msgs::Pose offset;
290 offset.orientation.w = 1;
314 const visualization_msgs::InteractiveMarkerFeedbackConstPtr* feedback,
341 Eigen::Affine3d pose;
345 pose = state->getGlobalLinkTransform(vj->
parent_frame).inverse(Eigen::Isometry) * pose;
347 state->setJointPositions(vj->
joint_name, pose);
381 if (new_error_state == old_error_state)
399 const geometry_msgs::Pose& offset, geometry_msgs::PoseStamped& tpose)
401 tpose.header = feedback->header;
402 tpose.pose = feedback->pose;
420 ROS_ERROR(
"Error transforming from frame '%s' to frame '%s'", tpose.header.frame_id.c_str(),
426 ROS_ERROR(
"Cannot transform from frame '%s' to frame '%s' (no TF instance provided)",
455 ROS_ERROR(
"setKinematicOptions() called from 2 different RobotInteraction instances.");
void clearPoseOffsets()
Clear the pose offset for all end-effectors and virtual joints.
const void * robot_interaction_
void updateStateJoint(robot_state::RobotState *state, const JointInteraction *vj, const geometry_msgs::Pose *pose, StateChangeCallbackFn *callback)
robot_state::GroupStateValidityCallbackFn state_validity_callback_
This is called to determine if the state is valid.
static void poseMsgToTF(const geometry_msgs::Pose &msg, Pose &bt)
bool getControlsVisible() const
std::string parent_link
The name of the link in the parent group that connects to the end-effector.
boost::function< void(InteractionHandler *handler, bool error_state_changed)> update_callback_
boost::mutex pose_map_lock_
bool getErrorState(const std::string &name) const
void setData(const T &input)
void clearLastMarkerPoses()
Clear the last interactive_marker command poses for all end-effectors and joints. ...
static const std::string DEFAULT
When used as key this means the default value.
std::set< std::string > error_state_
void poseMsgToEigen(const geometry_msgs::Pose &m, Eigen::Affine3d &e)
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
void clearMenuHandler()
Remove the menu handler for this interaction handler.
kinematics::KinematicsQueryOptions getKinematicsQueryOptions() const
void setControlsVisible(bool visible)
void setRobotInteraction(RobotInteraction *robot_interaction)
This should only be called by RobotInteraction. Associates this InteractionHandler to a RobotInteract...
KinematicOptionsMapPtr getKinematicOptionsMap()
void clearLastJointMarkerPose(const JointInteraction &vj)
Clear the last interactive_marker command pose for the given joint.
double timeout_seconds_
max time an IK attempt can take before we give up.
std::map< std::string, geometry_msgs::Pose > offset_map_
bool getLastJointMarkerPose(const JointInteraction &vj, geometry_msgs::PoseStamped &pose)
Get the last interactive_marker command pose for a joint.
void setKinematicsQueryOptionsForGroup(const std::string &group_name, const kinematics::KinematicsQueryOptions &options)
bool getLastEndEffectorMarkerPose(const EndEffectorInteraction &eef, geometry_msgs::PoseStamped &pose)
Get the last interactive_marker command pose for an end-effector.
void setPoseOffset(const EndEffectorInteraction &eef, const geometry_msgs::Pose &m)
Set the offset from EEF to its marker.
virtual void handleJoint(const JointInteraction &vj, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Update the internal state maintained by the handler using information from the received feedback mess...
virtual void handleEndEffector(const EndEffectorInteraction &eef, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Update the internal state maintained by the handler using information from the received feedback mess...
const std::string planning_frame_
void clearPoseOffset(const EndEffectorInteraction &eef)
Clear the interactive marker pose offset for the given end-effector.
bool getMeshesVisible() const
std::string eef_group
The name of the group that defines the group joints.
bool getPoseOffset(const EndEffectorInteraction &eef, geometry_msgs::Pose &m)
Get the offset from EEF to its marker.
std::shared_ptr< interactive_markers::MenuHandler > menu_handler_
static std::string fixName(std::string name)
boost::function< void(InteractionHandler *)> StateChangeCallbackFn
boost::shared_ptr< tf::Transformer > tf_
const std::shared_ptr< interactive_markers::MenuHandler > & getMenuHandler()
Get the menu handler that defines menus and callbacks for all interactive markers drawn by this inter...
kinematics::KinematicsQueryOptions options_
other options
virtual bool inError(const EndEffectorInteraction &eef) const
Check if the marker corresponding to this end-effector leads to an invalid state. ...
std::string parent_group
The name of the group that sustains the end-effector (usually an arm)
void updateStateGeneric(robot_state::RobotState *state, const GenericInteraction *g, const visualization_msgs::InteractiveMarkerFeedbackConstPtr *feedback, StateChangeCallbackFn *callback)
unsigned int max_attempts_
how many attempts before we give up.
boost::function< void(InteractionHandler *, bool)> InteractionHandlerCallbackFn
void modifyState(const ModifyStateFunction &modify)
void setIKTimeout(double timeout)
void clearLastEndEffectorMarkerPose(const EndEffectorInteraction &eef)
Clear the last interactive_marker command pose for the given end-effector.
bool transformFeedbackPose(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback, const geometry_msgs::Pose &offset, geometry_msgs::PoseStamped &tpose)
void setKinematicsQueryOptions(const kinematics::KinematicsQueryOptions &opt)
void updateStateEndEffector(robot_state::RobotState *state, const EndEffectorInteraction *eef, const geometry_msgs::Pose *pose, StateChangeCallbackFn *callback)
const InteractionHandlerCallbackFn & getUpdateCallback() const
std::map< std::string, geometry_msgs::PoseStamped > pose_map_
std::string marker_name_suffix
std::string parent_frame
The name of the frame that is a parent of this joint.
void setUpdateCallback(const InteractionHandlerCallbackFn &callback)
void setMeshesVisible(bool visible)
static const std::string ALL
When used as key this means set ALL keys (including default)
void clearError(void)
Clear any error settings. This makes the markers appear as if the state is no longer invalid...
Maintain a RobotState in a multithreaded environment.
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
virtual void handleGeneric(const GenericInteraction &g, const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
Update the internal state maintained by the handler using information from the received feedback mess...
std::string joint_name
The name of the joint.
InteractionHandler(const RobotInteractionPtr &robot_interaction, const std::string &name, const robot_state::RobotState &initial_robot_state, const boost::shared_ptr< tf::Transformer > &tf=boost::shared_ptr< tf::Transformer >())
void setIKAttempts(unsigned int attempts)
boost::mutex offset_map_lock_
bool setStateFromIK(robot_state::RobotState &state, const std::string &group, const std::string &tip, const geometry_msgs::Pose &pose) const
ProcessFeedbackFn process_feedback
void setMenuHandler(const std::shared_ptr< interactive_markers::MenuHandler > &mh)
Set the menu handler that defines menus and callbacks for all interactive markers drawn by this inter...
bool setErrorState(const std::string &name, bool new_error_state)
void setGroupStateValidityCallback(const robot_state::GroupStateValidityCallbackFn &callback)
KinematicOptionsMapPtr kinematic_options_map_