NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
planner::PlannerImplementation Class Referenceabstract

#include <planner.h>

Inheritance diagram for planner::PlannerImplementation:
Inheritance graph

Public Member Functions

 PlannerImplementation (std::string const &name, std::string const &description)
 
virtual ~PlannerImplementation ()
 
- Public Member Functions inherited from ff_util::FreeFlyerNodelet
 FreeFlyerNodelet (bool autostart_hb_timer=true)
 
 FreeFlyerNodelet (std::string const &name, bool autostart_hb_timer=true)
 
virtual ~FreeFlyerNodelet ()
 
void AssertFault (FaultKeys enum_key, std::string const &message, ros::Time time_fault_occurred=ros::Time::now())
 
void ClearAllFaults ()
 
void ClearFault (FaultKeys enum_key)
 
void PrintFaults ()
 
ros::NodeHandle * GetPlatformHandle (bool multithreaded=false)
 
ros::NodeHandle * GetPrivateHandle (bool multithreaded=false)
 
std::string GetName ()
 
std::string GetPlatform ()
 
std::string GetTransform (std::string const &child)
 

Protected Member Functions

virtual bool InitializePlanner (ros::NodeHandle *nh)=0
 
virtual void PlanCallback (ff_msgs::PlanGoal const &goal)=0
 
void PlanResult (ff_msgs::PlanResult const &result)
 
void PlanFeedback (ff_msgs::PlanFeedback const &feedback)
 
bool GetZones (std::vector< ff_msgs::Zone > &zones)
 
bool GetZonesMap (std::vector< signed char > &map, Vec3f &origin, Vec3i &dim, double &map_res)
 
bool GetFreeMap (pcl::PointCloud< pcl::PointXYZ > *points, float *resolution)
 
bool GetObstacleMap (pcl::PointCloud< pcl::PointXYZ > *points, float *resolution)
 
- Protected Member Functions inherited from ff_util::FreeFlyerNodelet
virtual void Reset ()
 
virtual void Sleep ()
 
virtual void Wakeup ()
 
void StopHeartbeat ()
 
void SendDiagnostics (const std::vector< diagnostic_msgs::KeyValue > &keyval)
 
void Setup (ros::NodeHandle &nh, ros::NodeHandle &nh_mt, std::string plugin_name)
 

Additional Inherited Members

- Public Types inherited from ff_util::FreeFlyerNodelet
enum  ResolveType : uint8_t { NAMESPACE = 0, TRANSFORM = 1, RESOURCE = 1 }
 
- Protected Attributes inherited from ff_util::FreeFlyerNodelet
std::map< std::string, int > faults_
 

Constructor & Destructor Documentation

◆ PlannerImplementation()

planner::PlannerImplementation::PlannerImplementation ( std::string const &  name,
std::string const &  description 
)
inlineexplicit

◆ ~PlannerImplementation()

virtual planner::PlannerImplementation::~PlannerImplementation ( )
inlinevirtual

Member Function Documentation

◆ GetFreeMap()

bool planner::PlannerImplementation::GetFreeMap ( pcl::PointCloud< pcl::PointXYZ > *  points,
float *  resolution 
)
inlineprotected

◆ GetObstacleMap()

bool planner::PlannerImplementation::GetObstacleMap ( pcl::PointCloud< pcl::PointXYZ > *  points,
float *  resolution 
)
inlineprotected

◆ GetZones()

bool planner::PlannerImplementation::GetZones ( std::vector< ff_msgs::Zone > &  zones)
inlineprotected

◆ GetZonesMap()

bool planner::PlannerImplementation::GetZonesMap ( std::vector< signed char > &  map,
Vec3f &  origin,
Vec3i &  dim,
double &  map_res 
)
inlineprotected

◆ InitializePlanner()

virtual bool planner::PlannerImplementation::InitializePlanner ( ros::NodeHandle *  nh)
protectedpure virtual

◆ PlanCallback()

virtual void planner::PlannerImplementation::PlanCallback ( ff_msgs::PlanGoal const &  goal)
protectedpure virtual

◆ PlanFeedback()

void planner::PlannerImplementation::PlanFeedback ( ff_msgs::PlanFeedback const &  feedback)
inlineprotected

◆ PlanResult()

void planner::PlannerImplementation::PlanResult ( ff_msgs::PlanResult const &  result)
inlineprotected

The documentation for this class was generated from the following file: