Public Member Functions | Private Member Functions | List of all members
hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNodelet Class Reference
Inheritance diagram for hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNodelet:
Inheritance graph
[legend]

Public Member Functions

 QuadrotorPoseEstimationNodelet (const SystemPtr &system=SystemPtr())
 
- Public Member Functions inherited from hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNode
virtual bool init ()
 
 QuadrotorPoseEstimationNode (const SystemPtr &system=SystemPtr(), const StatePtr &state=StatePtr())
 
virtual ~QuadrotorPoseEstimationNode ()
 
- Public Member Functions inherited from hector_pose_estimation::PoseEstimationNode
virtual void cleanup ()
 
 PoseEstimationNode (const SystemPtr &system=SystemPtr(), const StatePtr &state=StatePtr())
 
virtual void publish ()
 
virtual void reset ()
 
virtual ~PoseEstimationNode ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Member Functions

void onCleanup ()
 
void onInit ()
 
void onReset ()
 

Additional Inherited Members

- Protected Member Functions inherited from hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNode
void baroCallback (const hector_uav_msgs::AltimeterConstPtr &altimeter)
 
- Protected Member Functions inherited from hector_pose_estimation::PoseEstimationNode
void ahrsCallback (const sensor_msgs::ImuConstPtr &ahrs)
 
virtual ros::NodeHandlegetNodeHandle ()
 
virtual ros::NodeHandlegetPrivateNodeHandle ()
 
tf::TransformBroadcastergetTransformBroadcaster ()
 
tf::TransformListenergetTransformListener ()
 
void globalReferenceUpdated ()
 
void gpsCallback (const sensor_msgs::NavSatFixConstPtr &gps, const geometry_msgs::Vector3StampedConstPtr &gps_velocity)
 
void heightCallback (const geometry_msgs::PointStampedConstPtr &height)
 
void imuCallback (const sensor_msgs::ImuConstPtr &imu)
 
void magneticCallback (const geometry_msgs::Vector3StampedConstPtr &magnetic)
 
void poseupdateCallback (const geometry_msgs::PoseWithCovarianceStampedConstPtr &pose)
 
void publishWorldNavTransform (const ros::TimerEvent &=ros::TimerEvent())
 
void rollpitchCallback (const sensor_msgs::ImuConstPtr &attitude)
 
void syscommandCallback (const std_msgs::StringConstPtr &syscommand)
 
void twistupdateCallback (const geometry_msgs::TwistWithCovarianceStampedConstPtr &twist)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 
- Protected Attributes inherited from hector_pose_estimation::PoseEstimationNode
ros::Subscriber ahrs_subscriber_
 
ros::Publisher angular_velocity_bias_publisher_
 
ros::Publisher euler_publisher_
 
ros::Publisher geopose_publisher_
 
ros::Publisher global_fix_publisher_
 
ros::Publisher global_reference_publisher_
 
ros::Publisher gps_pose_publisher_
 
message_filters::Subscriber< sensor_msgs::NavSatFix > gps_subscriber_
 
message_filters::TimeSynchronizer< sensor_msgs::NavSatFix, geometry_msgs::Vector3Stamped > * gps_synchronizer_
 
message_filters::Subscriber< geometry_msgs::Vector3Stamped > gps_velocity_subscriber_
 
ros::Subscriber height_subscriber_
 
ros::Publisher imu_publisher_
 
ros::Subscriber imu_subscriber_
 
ros::Publisher linear_acceleration_bias_publisher_
 
ros::Subscriber magnetic_subscriber_
 
ros::NodeHandle nh_
 
std::string other_frame_
 
PoseEstimationpose_estimation_
 
ros::Publisher pose_publisher_
 
ros::Subscriber poseupdate_subscriber_
 
ros::NodeHandle private_nh_
 
bool publish_covariances_
 
bool publish_world_nav_transform_
 
ros::Duration publish_world_nav_transform_period_
 
ros::Timer publish_world_nav_transform_timer_
 
bool publish_world_other_transform_
 
ros::Subscriber rollpitch_subscriber_
 
geometry_msgs::PoseStamped sensor_pose_
 
double sensor_pose_pitch_
 
ros::Publisher sensor_pose_publisher_
 
double sensor_pose_roll_
 
double sensor_pose_yaw_
 
ros::Publisher state_publisher_
 
ros::Subscriber syscommand_subscriber_
 
std::string tf_prefix_
 
ros::Publisher timing_publisher_
 
tf::TransformBroadcaster transform_broadcaster_
 
tf::TransformListenertransform_listener_
 
std::vector< tf::StampedTransformtransforms_
 
ros::Subscriber twistupdate_subscriber_
 
ros::Publisher velocity_publisher_
 
geometry_msgs::TransformStamped world_nav_transform_
 
bool world_nav_transform_updated_
 
bool world_nav_transform_valid_
 

Detailed Description

Definition at line 34 of file pose_estimation_nodelet.cpp.

Constructor & Destructor Documentation

hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNodelet::QuadrotorPoseEstimationNodelet ( const SystemPtr system = SystemPtr())
inline

Definition at line 37 of file pose_estimation_nodelet.cpp.

Member Function Documentation

void hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNodelet::onCleanup ( )
inlineprivate

Definition at line 50 of file pose_estimation_nodelet.cpp.

void hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNodelet::onInit ( )
inlineprivatevirtual

Implements nodelet::Nodelet.

Definition at line 42 of file pose_estimation_nodelet.cpp.

void hector_quadrotor_pose_estimation::QuadrotorPoseEstimationNodelet::onReset ( )
inlineprivate

Definition at line 46 of file pose_estimation_nodelet.cpp.


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


hector_quadrotor_pose_estimation
Author(s): Johannes Meyer
autogenerated on Mon Jun 10 2019 13:37:01