monitor_utils.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2010, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
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


planning_environment
Author(s): Ioan Sucan
autogenerated on Thu Dec 12 2013 11:09:24