Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00037 #ifndef _MODEL_UTILS_H_
00038 #define _MODEL_UTILS_H_
00039
00040 #include <tf/tf.h>
00041 #include <planning_models/kinematic_state.h>
00042 #include <arm_navigation_msgs/RobotState.h>
00043 #include <arm_navigation_msgs/Constraints.h>
00044 #include <arm_navigation_msgs/OrderedCollisionOperations.h>
00045
00046 #include <planning_environment/util/kinematic_state_constraint_evaluator.h>
00047 #include <arm_navigation_msgs/Shape.h>
00048 #include <visualization_msgs/Marker.h>
00049 #include <arm_navigation_msgs/LinkPadding.h>
00050 #include <collision_space/environment.h>
00051 #include <arm_navigation_msgs/AllowedCollisionMatrix.h>
00052 #include <planning_environment/models/collision_models.h>
00053
00054 namespace planning_environment {
00055
00056
00057 bool setRobotStateAndComputeTransforms(const arm_navigation_msgs::RobotState &robot_state,
00058 planning_models::KinematicState& state);
00059
00060 void convertKinematicStateToRobotState(const planning_models::KinematicState& kinematic_state,
00061 const ros::Time& timestamp,
00062 const std::string& header_frame,
00063 arm_navigation_msgs::RobotState &robot_state);
00064
00065 void applyOrderedCollisionOperationsToMatrix(const arm_navigation_msgs::OrderedCollisionOperations &ord,
00066 collision_space::EnvironmentModel::AllowedCollisionMatrix& acm);
00067
00068 void convertFromACMToACMMsg(const collision_space::EnvironmentModel::AllowedCollisionMatrix& acm,
00069 arm_navigation_msgs::AllowedCollisionMatrix& matrix);
00070
00071 collision_space::EnvironmentModel::AllowedCollisionMatrix convertFromACMMsgToACM(const arm_navigation_msgs::AllowedCollisionMatrix& matrix);
00072
00073 bool applyOrderedCollisionOperationsListToACM(const arm_navigation_msgs::OrderedCollisionOperations& ordered_coll,
00074 const std::vector<std::string>& object_names,
00075 const std::vector<std::string>& att_names,
00076 const planning_models::KinematicModel* model,
00077 collision_space::EnvironmentModel::AllowedCollisionMatrix& matrix);
00078
00079 arm_navigation_msgs::AllowedCollisionMatrix
00080 applyOrderedCollisionOperationsToCollisionsModel(const CollisionModels* cm,
00081 const arm_navigation_msgs::OrderedCollisionOperations& ordered_coll,
00082 const std::vector<std::string>& object_names,
00083 const std::vector<std::string>& att_names);
00084
00085 void getAllKinematicStateStampedTransforms(const planning_models::KinematicState& state,
00086 std::vector<geometry_msgs::TransformStamped>& trans_vector,
00087 const ros::Time& stamp);
00088
00089 bool doesKinematicStateObeyConstraints(const planning_models::KinematicState& state,
00090 const arm_navigation_msgs::Constraints& constraints,
00091 bool verbose = false);
00092
00093 void setMarkerShapeFromShape(const arm_navigation_msgs::Shape &obj, visualization_msgs::Marker &mk);
00094
00095 void setMarkerShapeFromShape(const shapes::Shape *obj, visualization_msgs::Marker &mk, double padding = 0.0);
00096
00097 void convertFromLinkPaddingMapToLinkPaddingVector(const std::map<std::string, double>& link_padding_map,
00098 std::vector<arm_navigation_msgs::LinkPadding>& link_padding_vector);
00099
00100 void convertAllowedContactSpecificationMsgToAllowedContactVector(const std::vector<arm_navigation_msgs::AllowedContactSpecification>& acmv,
00101 std::vector<collision_space::EnvironmentModel::AllowedContact>& acv);
00102
00103 void getCollisionMarkersFromContactInformation(const std::vector<arm_navigation_msgs::ContactInformation>& contacts,
00104 const std::string& world_frame_id,
00105 visualization_msgs::MarkerArray& arr,
00106 const std_msgs::ColorRGBA& color,
00107 const ros::Duration& lifetime);
00108 }
00109 #endif