![]() |
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|

Public Member Functions | |
| Planner () | |
| ~Planner () | |
Public Member Functions inherited from planner::PlannerImplementation | |
| 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 | |
| bool | InitializePlanner (ros::NodeHandle *nh) |
| void | SendFeedback (ros::TimerEvent const &event) |
| bool | ReconfigureCallback (dynamic_reconfigure::Config &config) |
| void | AnimateTimer (ros::TimerEvent const &event) |
| traj_opt::Vec3Vec | sort_verticies (const traj_opt::Vec3Vec &in) |
| void | viz_cooridor (const std::vector< std::pair< traj_opt::MatD, traj_opt::VecD > > &cons_3d) |
| void | DiagnosticsCallback (const ros::TimerEvent &event) |
| void | PlanCallback (ff_msgs::PlanGoal const &goal) override |
| void | CancelCallback () |
Protected Member Functions inherited from planner::PlannerImplementation | |
| 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) |
Protected Attributes | |
| ff_util::ConfigServer | cfg_ |
| ros::Timer | timer_d_ |
| ros::Timer | timer_a_ |
| ros::Timer | timer_fb_ |
| boost::shared_ptr< traj_opt::NonlinearTrajectory > | trajectory_ |
| tf::Quaternion | start_orientation_ |
| tf::Vector3 | axis_ |
| double | planner_dt_ {0.5} |
| double | map_res_ {0.5} |
Protected Attributes inherited from ff_util::FreeFlyerNodelet | |
| std::map< std::string, int > | faults_ |
Additional Inherited Members | |
Public Types inherited from ff_util::FreeFlyerNodelet | |
| enum | ResolveType : uint8_t { NAMESPACE = 0, TRANSFORM = 1, RESOURCE = 1 } |
|
inline |
|
inline |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotectedvirtual |
Implements planner::PlannerImplementation.
|
inlineoverrideprotectedvirtual |
Implements planner::PlannerImplementation.
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
inlineprotected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |