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 _MONITOR_UTILS_H_
00038 #define _MONITOR_UTILS_H_
00039
00040 #include <tf/transform_listener.h>
00041 #include <geometry_msgs/PointStamped.h>
00042 #include <geometry_msgs/PoseStamped.h>
00043 #include <arm_navigation_msgs/Shape.h>
00044 #include <geometric_shapes/shape_operations.h>
00045 #include <arm_navigation_msgs/CollisionObject.h>
00046 #include <arm_navigation_msgs/AttachedCollisionObject.h>
00047 #include <planning_environment/models/collision_models.h>
00048 #include <pcl/point_cloud.h>
00049 #include <pcl/point_types.h>
00050 #include <sensor_msgs/JointState.h>
00051 #include <trajectory_msgs/JointTrajectory.h>
00052
00053 namespace planning_environment
00054 {
00055
00056 bool getLatestIdentityTransform(const std::string& to_frame,
00057 const std::string& from_frame,
00058 tf::TransformListener& tf,
00059 tf::Transform& pose);
00060
00061 bool createAndPoseShapes(tf::TransformListener& tf,
00062 const std::vector<arm_navigation_msgs::Shape>& orig_shapes,
00063 const std::vector<geometry_msgs::Pose>& orig_poses,
00064 const std_msgs::Header& header,
00065 const std::string& frame_to,
00066 std::vector<shapes::Shape*>& conv_shapes,
00067 std::vector<tf::Transform>& conv_poses);
00068
00069 bool processCollisionObjectMsg(const arm_navigation_msgs::CollisionObjectConstPtr &collision_object,
00070 tf::TransformListener& tf,
00071 CollisionModels* cm);
00072
00073 bool processAttachedCollisionObjectMsg(const arm_navigation_msgs::AttachedCollisionObjectConstPtr &attached_object,
00074 tf::TransformListener& tf,
00075 CollisionModels* cm);
00076
00077 void updateAttachedObjectBodyPoses(planning_environment::CollisionModels* cm,
00078 planning_models::KinematicState& state,
00079 tf::TransformListener& tf);
00080
00081 bool computeAttachedObjectPointCloudMask(const pcl::PointCloud<pcl::PointXYZ>& pcl_cloud,
00082 const std::string& sensor_frame,
00083 CollisionModels* cm,
00084 tf::TransformListener& tf,
00085 std::vector<int> &mask);
00086
00087 void updateAttachedObjectBodyPoses(planning_environment::CollisionModels* cm,
00088 planning_models::KinematicState& state,
00089 tf::TransformListener& tf);
00090
00091 bool configureForAttachedBodyMask(planning_models::KinematicState& state,
00092 planning_environment::CollisionModels* cm,
00093 tf::TransformListener& tf,
00094 const std::string& sensor_frame,
00095 const ros::Time& sensor_time,
00096 tf::Vector3& sensor_pos);
00097
00098 int computeAttachedObjectPointMask(const planning_environment::CollisionModels* cm,
00099 const tf::Vector3 &pt,
00100 const tf::Vector3 &sensor_pos);
00101
00102
00103 int closestStateOnTrajectory(const boost::shared_ptr<urdf::Model> &model,
00104 const trajectory_msgs::JointTrajectory &trajectory,
00105 const sensor_msgs::JointState &joint_state,
00106 unsigned int start,
00107 unsigned int end);
00108
00109 bool removeCompletedTrajectory(const boost::shared_ptr<urdf::Model> &model,
00110 const trajectory_msgs::JointTrajectory &trajectory_in,
00111 const sensor_msgs::JointState& current_state,
00112 trajectory_msgs::JointTrajectory &trajectory_out,
00113 bool zero_vel_acc);
00114 }
00115 #endif