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

#include <astrobee_gazebo.h>

Inheritance diagram for gazebo::FreeFlyerPlugin:
Inheritance graph

Public Member Functions

 FreeFlyerPlugin (std::string const &plugin_name, std::string const &plugin_frame, bool send_heartbeats=false)
 
virtual ~FreeFlyerPlugin ()
 
- 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

void InitializePlugin (std::string const &robot_name, std::string const &plugin_name)
 
void SetParentFrame (std::string const &parent)
 
std::string GetFrame (std::string target="", std::string delim="/")
 
virtual bool ExtrinsicsCallback (geometry_msgs::TransformStamped const *tf)=0
 
virtual void OnExtrinsicsReceived (ros::NodeHandle *nh)
 
void SetupExtrinsics (const ros::TimerEvent &event)
 
void CallbackThread ()
 
- Protected Member Functions inherited from ff_util::FreeFlyerNodelet
virtual void Initialize (ros::NodeHandle *nh)
 
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

std::string robot_name_
 
std::string plugin_name_
 
std::string plugin_frame_
 
std::string parent_frame_
 
ros::NodeHandle nh_
 
ros::NodeHandle nh_ff_
 
ros::NodeHandle nh_ff_mt_
 
std::shared_ptr< tf2_ros::TransformListener > listener_
 
ros::CallbackQueue callback_queue_
 
std::thread thread_
 
ros::Timer timer_
 
tf2_ros::Buffer buffer_
 
- 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 }
 

Constructor & Destructor Documentation

◆ FreeFlyerPlugin()

gazebo::FreeFlyerPlugin::FreeFlyerPlugin ( std::string const &  plugin_name,
std::string const &  plugin_frame,
bool  send_heartbeats = false 
)
explicit

◆ ~FreeFlyerPlugin()

gazebo::FreeFlyerPlugin::~FreeFlyerPlugin ( )
virtual

Member Function Documentation

◆ CallbackThread()

void gazebo::FreeFlyerPlugin::CallbackThread ( )
protected

◆ ExtrinsicsCallback()

◆ GetFrame()

std::string gazebo::FreeFlyerPlugin::GetFrame ( std::string  target = "",
std::string  delim = "/" 
)
protected

◆ InitializePlugin()

void gazebo::FreeFlyerPlugin::InitializePlugin ( std::string const &  robot_name,
std::string const &  plugin_name 
)
protected

◆ OnExtrinsicsReceived()

◆ SetParentFrame()

void gazebo::FreeFlyerPlugin::SetParentFrame ( std::string const &  parent)
protected

◆ SetupExtrinsics()

void gazebo::FreeFlyerPlugin::SetupExtrinsics ( const ros::TimerEvent &  event)
protected

Member Data Documentation

◆ buffer_

tf2_ros::Buffer gazebo::FreeFlyerPlugin::buffer_
protected

◆ callback_queue_

ros::CallbackQueue gazebo::FreeFlyerPlugin::callback_queue_
protected

◆ listener_

std::shared_ptr<tf2_ros::TransformListener> gazebo::FreeFlyerPlugin::listener_
protected

◆ nh_

ros::NodeHandle gazebo::FreeFlyerPlugin::nh_
protected

◆ nh_ff_

ros::NodeHandle gazebo::FreeFlyerPlugin::nh_ff_
protected

◆ nh_ff_mt_

ros::NodeHandle gazebo::FreeFlyerPlugin::nh_ff_mt_
protected

◆ parent_frame_

std::string gazebo::FreeFlyerPlugin::parent_frame_
protected

◆ plugin_frame_

std::string gazebo::FreeFlyerPlugin::plugin_frame_
protected

◆ plugin_name_

std::string gazebo::FreeFlyerPlugin::plugin_name_
protected

◆ robot_name_

std::string gazebo::FreeFlyerPlugin::robot_name_
protected

◆ thread_

std::thread gazebo::FreeFlyerPlugin::thread_
protected

◆ timer_

ros::Timer gazebo::FreeFlyerPlugin::timer_
protected

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