publisher.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
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 copyright holder 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 HOLDER 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 
00035 #ifndef DWB_LOCAL_PLANNER_PUBLISHER_H
00036 #define DWB_LOCAL_PLANNER_PUBLISHER_H
00037 
00038 #include <ros/ros.h>
00039 #include <nav_core2/common.h>
00040 #include <dwb_local_planner/trajectory_critic.h>
00041 #include <dwb_msgs/LocalPlanEvaluation.h>
00042 #include <vector>
00043 
00044 namespace dwb_local_planner
00045 {
00046 
00059 class DWBPublisher
00060 {
00061 public:
00066   void initialize(ros::NodeHandle& nh);
00067 
00072   bool shouldRecordEvaluation() { return publish_evaluation_ || publish_trajectories_; }
00073 
00077   void publishEvaluation(std::shared_ptr<dwb_msgs::LocalPlanEvaluation> results);
00078   void publishLocalPlan(const std_msgs::Header& header, const dwb_msgs::Trajectory2D& traj);
00079   void publishCostGrid(const nav_core2::Costmap::Ptr costmap, const std::vector<TrajectoryCritic::Ptr> critics);
00080   void publishGlobalPlan(const nav_2d_msgs::Path2D plan);
00081   void publishTransformedPlan(const nav_2d_msgs::Path2D plan);
00082   void publishLocalPlan(const nav_2d_msgs::Path2D plan);
00083   void publishInputParams(const nav_grid::NavGridInfo& info, const geometry_msgs::Pose2D& start_pose,
00084                           const nav_2d_msgs::Twist2D& velocity, const geometry_msgs::Pose2D& goal_pose);
00085 
00086 protected:
00087   void publishTrajectories(const dwb_msgs::LocalPlanEvaluation& results);
00088 
00089   // Helper function for publishing other plans
00090   void publishGenericPlan(const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag);
00091 
00092   // Flags for turning on/off publishing specific components
00093   bool publish_evaluation_, publish_global_plan_, publish_transformed_, publish_local_plan_, publish_trajectories_;
00094   bool publish_cost_grid_pc_, publish_input_params_;
00095 
00096   // Marker Lifetime
00097   ros::Duration marker_lifetime_;
00098 
00099   // Publisher Objects
00100   ros::Publisher eval_pub_, global_pub_, transformed_pub_, local_pub_, marker_pub_, cost_grid_pc_pub_,
00101                  info_pub_, pose_pub_, goal_pub_, velocity_pub_;
00102 };
00103 
00104 }  // namespace dwb_local_planner
00105 
00106 #endif  // DWB_LOCAL_PLANNER_PUBLISHER_H


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:09:38