All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends
Public Member Functions | Protected Member Functions | Private Attributes
hector_pose_estimation::PoseEstimationTaskContext Class Reference

#include <taskcontext.h>

Inheritance diagram for hector_pose_estimation::PoseEstimationTaskContext:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 PoseEstimationTaskContext (const std::string &name="PoseEsimation", const SystemPtr &system=SystemPtr())
void reset ()
void updateOutputs ()
virtual ~PoseEstimationTaskContext ()

Protected Member Functions

void cleanupHook ()
void commandCallback (RTT::base::PortInterface *)
bool configureHook ()
bool startHook ()
void stopHook ()
void updateHook ()

Private Attributes

geometry_msgs::Vector3Stamped angular_velocity_bias_
RTT::OutputPort
< geometry_msgs::Vector3Stamped > 
angular_velocity_bias_output_
RTT::InputPort< std_msgs::String > command_input_
sensor_msgs::NavSatFix global_position_
RTT::OutputPort
< sensor_msgs::NavSatFix > 
global_position_output_
sensor_msgs::NavSatFix gps_
RTT::InputPort
< sensor_msgs::NavSatFix > 
gps_input_
geometry_msgs::Vector3Stamped gps_velocity_
RTT::InputPort
< geometry_msgs::Vector3Stamped > 
gps_velocity_input_
geometry_msgs::PointStamped height_
RTT::InputPort
< geometry_msgs::PointStamped > 
height_input_
sensor_msgs::Imu imu_in_
RTT::InputPort< sensor_msgs::Imu > imu_input_
sensor_msgs::Imu imu_out_
RTT::OutputPort< sensor_msgs::Imu > imu_output_
geometry_msgs::Vector3Stamped linear_acceleration_bias_
RTT::OutputPort
< geometry_msgs::Vector3Stamped > 
linear_acceleration_bias_output_
geometry_msgs::Vector3Stamped magnetic_
RTT::InputPort
< geometry_msgs::Vector3Stamped > 
magnetic_input_
ros::NodeHandle node_handle_
std::string param_namespace_
geometry_msgs::PoseStamped pose_
RTT::OutputPort
< geometry_msgs::PoseStamped > 
pose_output_
geometry_msgs::PoseWithCovarianceStamped pose_update_
RTT::InputPort
< geometry_msgs::PoseWithCovarianceStamped > 
pose_update_input_
nav_msgs::Odometry state_
RTT::OutputPort
< nav_msgs::Odometry > 
state_output_
geometry_msgs::Vector3Stamped velocity_
RTT::OutputPort
< geometry_msgs::Vector3Stamped > 
velocity_output_

Detailed Description

Definition at line 56 of file taskcontext.h.


Constructor & Destructor Documentation

hector_pose_estimation::PoseEstimationTaskContext::PoseEstimationTaskContext ( const std::string &  name = "PoseEsimation",
const SystemPtr system = SystemPtr() 
)

Definition at line 44 of file taskcontext.cpp.

Definition at line 86 of file taskcontext.cpp.


Member Function Documentation

Definition at line 105 of file taskcontext.cpp.

void hector_pose_estimation::PoseEstimationTaskContext::commandCallback ( RTT::base::PortInterface *  ) [protected]

Definition at line 218 of file taskcontext.cpp.

Definition at line 92 of file taskcontext.cpp.

Reimplemented from hector_pose_estimation::PoseEstimation.

Definition at line 212 of file taskcontext.cpp.

Definition at line 110 of file taskcontext.cpp.

Definition at line 115 of file taskcontext.cpp.

Definition at line 119 of file taskcontext.cpp.

Definition at line 165 of file taskcontext.cpp.


Member Data Documentation

Definition at line 116 of file taskcontext.h.

RTT::OutputPort<geometry_msgs::Vector3Stamped> hector_pose_estimation::PoseEstimationTaskContext::angular_velocity_bias_output_ [private]

Definition at line 115 of file taskcontext.h.

RTT::InputPort<std_msgs::String> hector_pose_estimation::PoseEstimationTaskContext::command_input_ [private]

Definition at line 119 of file taskcontext.h.

Definition at line 113 of file taskcontext.h.

RTT::OutputPort<sensor_msgs::NavSatFix> hector_pose_estimation::PoseEstimationTaskContext::global_position_output_ [private]

Definition at line 112 of file taskcontext.h.

Definition at line 97 of file taskcontext.h.

RTT::InputPort<sensor_msgs::NavSatFix> hector_pose_estimation::PoseEstimationTaskContext::gps_input_ [private]

Definition at line 95 of file taskcontext.h.

Definition at line 98 of file taskcontext.h.

RTT::InputPort<geometry_msgs::Vector3Stamped> hector_pose_estimation::PoseEstimationTaskContext::gps_velocity_input_ [private]

Definition at line 96 of file taskcontext.h.

geometry_msgs::PointStamped hector_pose_estimation::PoseEstimationTaskContext::height_ [private]

Definition at line 92 of file taskcontext.h.

RTT::InputPort<geometry_msgs::PointStamped> hector_pose_estimation::PoseEstimationTaskContext::height_input_ [private]

Definition at line 91 of file taskcontext.h.

Definition at line 79 of file taskcontext.h.

RTT::InputPort<sensor_msgs::Imu> hector_pose_estimation::PoseEstimationTaskContext::imu_input_ [private]

Definition at line 78 of file taskcontext.h.

Definition at line 104 of file taskcontext.h.

RTT::OutputPort<sensor_msgs::Imu> hector_pose_estimation::PoseEstimationTaskContext::imu_output_ [private]

Definition at line 103 of file taskcontext.h.

Definition at line 117 of file taskcontext.h.

RTT::OutputPort<geometry_msgs::Vector3Stamped> hector_pose_estimation::PoseEstimationTaskContext::linear_acceleration_bias_output_ [private]

Definition at line 115 of file taskcontext.h.

geometry_msgs::Vector3Stamped hector_pose_estimation::PoseEstimationTaskContext::magnetic_ [private]

Definition at line 85 of file taskcontext.h.

RTT::InputPort<geometry_msgs::Vector3Stamped> hector_pose_estimation::PoseEstimationTaskContext::magnetic_input_ [private]

Definition at line 84 of file taskcontext.h.

Definition at line 121 of file taskcontext.h.

Definition at line 122 of file taskcontext.h.

geometry_msgs::PoseStamped hector_pose_estimation::PoseEstimationTaskContext::pose_ [private]

Definition at line 107 of file taskcontext.h.

RTT::OutputPort<geometry_msgs::PoseStamped> hector_pose_estimation::PoseEstimationTaskContext::pose_output_ [private]

Definition at line 106 of file taskcontext.h.

geometry_msgs::PoseWithCovarianceStamped hector_pose_estimation::PoseEstimationTaskContext::pose_update_ [private]

Definition at line 82 of file taskcontext.h.

RTT::InputPort<geometry_msgs::PoseWithCovarianceStamped> hector_pose_estimation::PoseEstimationTaskContext::pose_update_input_ [private]

Definition at line 81 of file taskcontext.h.

Reimplemented from hector_pose_estimation::PoseEstimation.

Definition at line 101 of file taskcontext.h.

RTT::OutputPort<nav_msgs::Odometry> hector_pose_estimation::PoseEstimationTaskContext::state_output_ [private]

Definition at line 100 of file taskcontext.h.

geometry_msgs::Vector3Stamped hector_pose_estimation::PoseEstimationTaskContext::velocity_ [private]

Definition at line 110 of file taskcontext.h.

RTT::OutputPort<geometry_msgs::Vector3Stamped> hector_pose_estimation::PoseEstimationTaskContext::velocity_output_ [private]

Definition at line 109 of file taskcontext.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


rtt_hector_pose_estimation
Author(s): Johannes Meyer
autogenerated on Mon Jul 15 2013 16:49:00