Classes | Functions
ftc_local_planner Namespace Reference

Classes

class  FTCPlanner
class  JoinCostmap

Functions

bool getXPose (const tf::TransformListener &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const std::string &global_frame, tf::Stamped< tf::Pose > &goal_pose, int plan_point)
 Returns X pose in plan.

Detailed Description

Copyright (c) 2016, Marek Felix All rights reserved.

Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:

1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.

2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.

3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.


Function Documentation

bool ftc_local_planner::getXPose ( const tf::TransformListener tf,
const std::vector< geometry_msgs::PoseStamped > &  global_plan,
const std::string &  global_frame,
tf::Stamped< tf::Pose > &  goal_pose,
int  plan_point 
)

Returns X pose in plan.

Parameters:
tfA reference to a transform listener
global_planThe plan being followed
global_frameThe global frame of the local planner
goal_posethe pose to copy into
Returns:
True if achieved, false otherwise

Definition at line 22 of file transform_global_plan.cpp.



asr_ftc_local_planner
Author(s): Marek Felix
autogenerated on Wed Jun 19 2019 19:38:18