Public Member Functions | Protected Member Functions | Protected Attributes
RobotLocalization::RosFilter< T > Class Template Reference

#include <ros_filter.h>

List of all members.

Public Member Functions

void accelerationCallback (const sensor_msgs::Imu::ConstPtr &msg, const CallbackData &callbackData, const std::string &targetFrame)
 Callback method for receiving all acceleration (IMU) messages.
void controlCallback (const geometry_msgs::Twist::ConstPtr &msg)
 Callback method for receiving non-stamped control input.
void controlCallback (const geometry_msgs::TwistStamped::ConstPtr &msg)
 Callback method for receiving stamped control input.
void enqueueMeasurement (const std::string &topicName, const Eigen::VectorXd &measurement, const Eigen::MatrixXd &measurementCovariance, const std::vector< int > &updateVector, const double mahalanobisThresh, const ros::Time &time)
 Adds a measurement to the queue of measurements to be processed.
void forceTwoD (Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance, std::vector< int > &updateVector)
 Method for zeroing out 3D variables within measurements.
bool getFilteredAccelMessage (geometry_msgs::AccelWithCovarianceStamped &message)
 Retrieves the EKF's acceleration output for broadcasting.
bool getFilteredOdometryMessage (nav_msgs::Odometry &message)
 Retrieves the EKF's output for broadcasting.
void imuCallback (const sensor_msgs::Imu::ConstPtr &msg, const std::string &topicName, const CallbackData &poseCallbackData, const CallbackData &twistCallbackData, const CallbackData &accelCallbackData)
 Callback method for receiving all IMU messages.
void integrateMeasurements (const ros::Time &currentTime)
 Processes all measurements in the measurement queue, in temporal order.
void loadParams ()
 Loads all parameters from file.
void odometryCallback (const nav_msgs::Odometry::ConstPtr &msg, const std::string &topicName, const CallbackData &poseCallbackData, const CallbackData &twistCallbackData)
 Callback method for receiving all odometry messages.
void poseCallback (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, const CallbackData &callbackData, const std::string &targetFrame, const bool imuData)
 Callback method for receiving all pose messages.
 RosFilter (std::vector< double > args=std::vector< double >())
 Constructor.
void run ()
 Main run method.
void setPoseCallback (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg)
 Callback method for manually setting/resetting the internal pose estimate.
bool setPoseSrvCallback (robot_localization::SetPose::Request &request, robot_localization::SetPose::Response &)
 Service callback for manually setting/resetting the internal pose estimate.
std::string tfFailureReasonString (const tf2_ros::FilterFailureReason reason)
 Converts tf message filter failures to strings.
void twistCallback (const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, const CallbackData &callbackData, const std::string &targetFrame)
 Callback method for receiving all twist messages.
 ~RosFilter ()
 Destructor.

Protected Member Functions

void addDiagnostic (const int errLevel, const std::string &topicAndClass, const std::string &message, const bool staticDiag)
 Adds a diagnostic message to the accumulating map and updates the error level.
void aggregateDiagnostics (diagnostic_updater::DiagnosticStatusWrapper &wrapper)
 Aggregates all diagnostics so they can be published.
void clearExpiredHistory (const double cutoffTime)
 Removes measurements and filter states older than the given cutoff time.
void copyCovariance (const double *arr, Eigen::MatrixXd &covariance, const std::string &topicName, const std::vector< int > &updateVector, const size_t offset, const size_t dimension)
 Utility method for copying covariances from ROS covariance arrays to Eigen matrices.
void copyCovariance (const Eigen::MatrixXd &covariance, double *arr, const size_t dimension)
 Utility method for copying covariances from Eigen matrices to ROS covariance arrays.
std::vector< int > loadUpdateConfig (const std::string &topicName)
 Loads fusion settings from the config file.
bool prepareAcceleration (const sensor_msgs::Imu::ConstPtr &msg, const std::string &topicName, const std::string &targetFrame, std::vector< int > &updateVector, Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance)
 Prepares an IMU message's linear acceleration for integration into the filter.
bool preparePose (const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &msg, const std::string &topicName, const std::string &targetFrame, const bool differential, const bool relative, const bool imuData, std::vector< int > &updateVector, Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance)
 Prepares a pose message for integration into the filter.
bool prepareTwist (const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &msg, const std::string &topicName, const std::string &targetFrame, std::vector< int > &updateVector, Eigen::VectorXd &measurement, Eigen::MatrixXd &measurementCovariance)
 Prepares a twist message for integration into the filter.
bool revertTo (const double time)
 Finds the latest filter state before the given timestamp and makes it the current state again.
void saveFilterState (FilterBase &filter)
 Saves the current filter state in the queue of previous filter states.

Protected Attributes

std::string baseLinkFrameId_
 tf frame name for the robot's body frame
ros::Subscriber controlSub_
 Subscribes to the control input topic.
std::ofstream debugStream_
 Used for outputting debug messages.
diagnostic_updater::Updater diagnosticUpdater_
 Used for updating the diagnostics.
int dynamicDiagErrorLevel_
 The max (worst) dynamic diagnostic level.
std::map< std::string,
std::string > 
dynamicDiagnostics_
 This object accumulates dynamic diagnostics, e.g., diagnostics relating to sensor data.
T filter_
 Our filter (EKF, UKF, etc.)
FilterStateHistoryDeque filterStateHistory_
 An implicitly time ordered queue of past filter states used for smoothing.
double frequency_
 The frequency of the run loop.
double gravitationalAcc_
 What is the acceleration in Z due to gravity (m/s^2)? Default is +9.80665.
double historyLength_
 The depth of the history we track for smoothing/delayed measurement processing.
std::map< std::string,
tf2::Transform
initialMeasurements_
 Stores the first measurement from each topic for relative measurements.
std::map< std::string, ros::TimelastMessageTimes_
 Store the last time a message from each topic was received.
ros::Time lastSetPoseTime_
 Store the last time set pose message was received.
Eigen::VectorXd latestControl_
 The most recent control input.
ros::Time latestControlTime_
 The time of the most recent control input.
std::string mapFrameId_
 tf frame name for the robot's map (world-fixed) frame
MeasurementHistoryDeque measurementHistory_
 A deque of previous measurements which is implicitly ordered from earliest to latest measurement.
MeasurementQueue measurementQueue_
 We process measurements by queueing them up in callbacks and processing them all at once within each iteration.
ros::NodeHandle nh_
 Node handle.
ros::NodeHandle nhLocal_
 Local node handle (for params)
std::string odomFrameId_
 tf frame name for the robot's odometry (world-fixed) frame
std::map< std::string,
Eigen::MatrixXd > 
previousMeasurementCovariances_
 We also need the previous covariance matrix for differential data.
std::map< std::string,
tf2::Transform
previousMeasurements_
 Stores the last measurement from a given topic for differential integration.
bool printDiagnostics_
 Whether or not we print diagnostic messages to the /diagnostics topic.
bool publishAcceleration_
 Whether we publish the acceleration.
bool publishTransform_
 Whether we publish the transform from the world_frame to the base_link_frame.
std::map< std::string, bool > removeGravitationalAcc_
 If including acceleration for each IMU input, whether or not we remove acceleration due to gravity.
ros::ServiceServer setPoseSrv_
 Service that allows another node to change the current state and recieve a confirmation. Uses a custom SetPose service.
ros::Subscriber setPoseSub_
 Subscribes to the set_pose topic (usually published from rviz). Message type is geometry_msgs/PoseWithCovarianceStamped.
bool smoothLaggedData_
 Whether or not we use smoothing.
std::vector< std::string > stateVariableNames_
 Contains the state vector variable names in string format.
int staticDiagErrorLevel_
 The max (worst) static diagnostic level.
std::map< std::string,
std::string > 
staticDiagnostics_
 This object accumulates static diagnostics, e.g., diagnostics relating to the configuration parameters.
tf2_ros::Buffer tfBuffer_
 Transform buffer for managing coordinate transforms.
tf2_ros::TransformListener tfListener_
 Transform listener for receiving transforms.
ros::Duration tfTimeOffset_
 For future (or past) dating the world_frame->base_link_frame transform.
ros::Duration tfTimeout_
 Parameter that specifies the how long we wait for a transform to become available.
std::vector< ros::SubscribertopicSubs_
 Vector to hold our subscribers until they go out of scope.
bool twoDMode_
 Whether or not we're in 2D mode.
bool useControl_
 Whether or not we use a control term.
geometry_msgs::TransformStamped worldBaseLinkTransMsg_
 Message that contains our latest transform (i.e., state)
std::string worldFrameId_
 tf frame name that is the parent frame of the transform that this node will calculate and broadcast.

Detailed Description

template<class T>
class RobotLocalization::RosFilter< T >

Definition at line 104 of file ros_filter.h.


Constructor & Destructor Documentation

template<typename T >
RobotLocalization::RosFilter< T >::RosFilter ( std::vector< double >  args = std::vector<double>()) [explicit]

Constructor.

The RosFilter constructor makes sure that anyone using this template is doing so with the correct object type

Definition at line 50 of file ros_filter.cpp.

template<typename T >
RobotLocalization::RosFilter< T >::~RosFilter ( )

Destructor.

Clears out the message filters and topic subscribers.

Definition at line 90 of file ros_filter.cpp.


Member Function Documentation

template<typename T >
void RobotLocalization::RosFilter< T >::accelerationCallback ( const sensor_msgs::Imu::ConstPtr &  msg,
const CallbackData callbackData,
const std::string &  targetFrame 
)

Callback method for receiving all acceleration (IMU) messages.

Parameters:
[in]msg- The ROS IMU message to take in.
[in]callbackData- Relevant static callback data
[in]targetFrame- The target frame_id into which to transform the data

Definition at line 97 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::addDiagnostic ( const int  errLevel,
const std::string &  topicAndClass,
const std::string &  message,
const bool  staticDiag 
) [protected]

Adds a diagnostic message to the accumulating map and updates the error level.

Parameters:
[in]errLevel- The error level of the diagnostic
[in]topicAndClass- The sensor topic (if relevant) and class of diagnostic
[in]message- Details of the diagnostic
[in]staticDiag- Whether or not this diagnostic information is static

Definition at line 1976 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::aggregateDiagnostics ( diagnostic_updater::DiagnosticStatusWrapper wrapper) [protected]

Aggregates all diagnostics so they can be published.

Parameters:
[in]wrapper- The diagnostic status wrapper to update

Definition at line 1994 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::clearExpiredHistory ( const double  cutoffTime) [protected]

Removes measurements and filter states older than the given cutoff time.

Parameters:
[in]cutoffTime- Measurements and states older than this time will be dropped.

Definition at line 2926 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::controlCallback ( const geometry_msgs::Twist::ConstPtr &  msg)

Callback method for receiving non-stamped control input.

Parameters:
[in]msg- The ROS twist message to take in

Definition at line 176 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::controlCallback ( const geometry_msgs::TwistStamped::ConstPtr &  msg)

Callback method for receiving stamped control input.

Parameters:
[in]msg- The ROS stamped twist message to take in

Definition at line 186 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::copyCovariance ( const double *  arr,
Eigen::MatrixXd &  covariance,
const std::string &  topicName,
const std::vector< int > &  updateVector,
const size_t  offset,
const size_t  dimension 
) [protected]

Utility method for copying covariances from ROS covariance arrays to Eigen matrices.

This method copies the covariances and also does some data validation, which is why it requires more parameters than just the covariance containers.

Parameters:
[in]arr- The source array for the covariance data
[in]covariance- The destination matrix for the covariance data
[in]topicName- The name of the source data topic (for debug purposes)
[in]updateVector- The update vector for the source topic
[in]offset- The "starting" location within the array/update vector
[in]dimension- The number of values to copy, starting at the offset

Definition at line 2047 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::copyCovariance ( const Eigen::MatrixXd &  covariance,
double *  arr,
const size_t  dimension 
) [protected]

Utility method for copying covariances from Eigen matrices to ROS covariance arrays.

Parameters:
[in]covariance- The source matrix for the covariance data
[in]arr- The destination array
[in]dimension- The number of values to copy

Definition at line 2110 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::enqueueMeasurement ( const std::string &  topicName,
const Eigen::VectorXd &  measurement,
const Eigen::MatrixXd &  measurementCovariance,
const std::vector< int > &  updateVector,
const double  mahalanobisThresh,
const ros::Time time 
)

Adds a measurement to the queue of measurements to be processed.

Parameters:
[in]topicName- The name of the measurement source (only used for debugging)
[in]measurement- The measurement to enqueue
[in]measurementCovariance- The covariance of the measurement
[in]updateVector- The boolean vector that specifies which variables to update from this measurement
[in]mahalanobisThresh- Threshold, expressed as a Mahalanobis distance, for outlier rejection
[in]time- The time of arrival (in seconds)

Definition at line 209 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::forceTwoD ( Eigen::VectorXd &  measurement,
Eigen::MatrixXd &  measurementCovariance,
std::vector< int > &  updateVector 
)

Method for zeroing out 3D variables within measurements.

Parameters:
[out]measurement- The measurement whose 3D variables will be zeroed out
[out]measurementCovariance- The covariance of the measurement
[out]updateVector- The boolean update vector of the measurement

If we're in 2D mode, then for every measurement from every sensor, we call this. It sets the 3D variables to 0, gives those variables tiny variances, and sets their updateVector values to 1.

Definition at line 230 of file ros_filter.cpp.

template<typename T >
bool RobotLocalization::RosFilter< T >::getFilteredAccelMessage ( geometry_msgs::AccelWithCovarianceStamped &  message)

Retrieves the EKF's acceleration output for broadcasting.

Parameters:
[out]message- The standard ROS acceleration message to be filled
Returns:
true if the filter is initialized, false otherwise

Fill out the accel_msg

Definition at line 319 of file ros_filter.cpp.

template<typename T >
bool RobotLocalization::RosFilter< T >::getFilteredOdometryMessage ( nav_msgs::Odometry &  message)

Retrieves the EKF's output for broadcasting.

Parameters:
[out]message- The standard ROS odometry message to be filled
Returns:
true if the filter is initialized, false otherwise

Definition at line 260 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::imuCallback ( const sensor_msgs::Imu::ConstPtr &  msg,
const std::string &  topicName,
const CallbackData poseCallbackData,
const CallbackData twistCallbackData,
const CallbackData accelCallbackData 
)

Callback method for receiving all IMU messages.

Parameters:
[in]msg- The ROS IMU message to take in.
[in]topicName- The topic name for the IMU message (only used for debug output)
[in]poseCallbackData- Relevant static callback data for orientation variables
[in]twistCallbackData- Relevant static callback data for angular velocity variables
[in]accelCallbackData- Relevant static callback data for linear acceleration variables

This method separates out the orientation, angular velocity, and linear acceleration data and passed each on to its respective callback.

Definition at line 354 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::integrateMeasurements ( const ros::Time currentTime)

Processes all measurements in the measurement queue, in temporal order.

Parameters:
[in]currentTime- The time at which to carry out integration (the current time)

Definition at line 468 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::loadParams ( )

Loads all parameters from file.

Definition at line 578 of file ros_filter.cpp.

template<typename T >
std::vector< int > RobotLocalization::RosFilter< T >::loadUpdateConfig ( const std::string &  topicName) [protected]

Loads fusion settings from the config file.

Parameters:
[in]topicName- The name of the topic for which to load settings
Returns:
The boolean vector of update settings for each variable for this topic

Definition at line 2124 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::odometryCallback ( const nav_msgs::Odometry::ConstPtr &  msg,
const std::string &  topicName,
const CallbackData poseCallbackData,
const CallbackData twistCallbackData 
)

Callback method for receiving all odometry messages.

Parameters:
[in]msg- The ROS odometry message to take in.
[in]topicName- The topic name for the odometry message (only used for debug output)
[in]poseCallbackData- Relevant static callback data for pose variables
[in]twistCallbackData- Relevant static callback data for twist variables

This method simply separates out the pose and twist data into two new messages, and passes them into their respective callbacks

Definition at line 1511 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::poseCallback ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  msg,
const CallbackData callbackData,
const std::string &  targetFrame,
const bool  imuData 
)

Callback method for receiving all pose messages.

Parameters:
[in]msg- The ROS stamped pose with covariance message to take in
[in]callbackData- Relevant static callback data
[in]targetFrame- The target frame_id into which to transform the data
[in]imuData- Whether this data comes from an IMU

Definition at line 1560 of file ros_filter.cpp.

template<typename T >
bool RobotLocalization::RosFilter< T >::prepareAcceleration ( const sensor_msgs::Imu::ConstPtr &  msg,
const std::string &  topicName,
const std::string &  targetFrame,
std::vector< int > &  updateVector,
Eigen::VectorXd &  measurement,
Eigen::MatrixXd &  measurementCovariance 
) [protected]

Prepares an IMU message's linear acceleration for integration into the filter.

Parameters:
[in]msg- The IMU message to prepare
[in]topicName- The name of the topic over which this message was received
[in]targetFrame- The target tf frame
[in]updateVector- The update vector for the data source
[in]measurement- The twist data converted to a measurement
[in]measurementCovariance- The covariance of the converted measurement

Definition at line 2160 of file ros_filter.cpp.

template<typename T >
bool RobotLocalization::RosFilter< T >::preparePose ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  msg,
const std::string &  topicName,
const std::string &  targetFrame,
const bool  differential,
const bool  relative,
const bool  imuData,
std::vector< int > &  updateVector,
Eigen::VectorXd &  measurement,
Eigen::MatrixXd &  measurementCovariance 
) [protected]

Prepares a pose message for integration into the filter.

Parameters:
[in]msg- The pose message to prepare
[in]topicName- The name of the topic over which this message was received
[in]targetFrame- The target tf frame
[in]differential- Whether we're carrying out differential integration
[in]relative- Whether this measurement is processed relative to the first
[in]imuData- Whether this measurement is from an IMU
[in,out]updateVector- The update vector for the data source
[out]measurement- The pose data converted to a measurement
[out]measurementCovariance- The covariance of the converted measurement
Returns:
true indicates that the measurement was successfully prepared, false otherwise

Definition at line 2328 of file ros_filter.cpp.

template<typename T >
bool RobotLocalization::RosFilter< T >::prepareTwist ( const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &  msg,
const std::string &  topicName,
const std::string &  targetFrame,
std::vector< int > &  updateVector,
Eigen::VectorXd &  measurement,
Eigen::MatrixXd &  measurementCovariance 
) [protected]

Prepares a twist message for integration into the filter.

Parameters:
[in]msg- The twist message to prepare
[in]topicName- The name of the topic over which this message was received
[in]targetFrame- The target tf frame
[in,out]updateVector- The update vector for the data source
[out]measurement- The twist data converted to a measurement
[out]measurementCovariance- The covariance of the converted measurement
Returns:
true indicates that the measurement was successfully prepared, false otherwise

Definition at line 2716 of file ros_filter.cpp.

template<typename T >
bool RobotLocalization::RosFilter< T >::revertTo ( const double  time) [protected]

Finds the latest filter state before the given timestamp and makes it the current state again.

This method also inserts all measurements between the older filter timestamp and now into the measurements queue.

Parameters:
[in]time- The time to which the filter state should revert
Returns:
True if restoring the filter succeeded. False if not.

Definition at line 2880 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::run ( )

Main run method.

Definition at line 1657 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::saveFilterState ( FilterBase filter) [protected]

Saves the current filter state in the queue of previous filter states.

These measurements will be used in backwards smoothing in the event that older measurements come in.

Parameters:
[in]filter- The filter base object whose state we want to save

Definition at line 2866 of file ros_filter.cpp.

template<typename T >
void RobotLocalization::RosFilter< T >::setPoseCallback ( const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &  msg)

Callback method for manually setting/resetting the internal pose estimate.

Parameters:
[in]msg- The ROS stamped pose with covariance message to take in

Definition at line 1826 of file ros_filter.cpp.

template<typename T >
bool RobotLocalization::RosFilter< T >::setPoseSrvCallback ( robot_localization::SetPose::Request &  request,
robot_localization::SetPose::Response &   
)

Service callback for manually setting/resetting the internal pose estimate.

Parameters:
[in]request- Custom service request with pose information
Returns:
true if successful, false if not

Definition at line 1879 of file ros_filter.cpp.

template<class T >
std::string RobotLocalization::RosFilter< T >::tfFailureReasonString ( const tf2_ros::FilterFailureReason  reason)

Converts tf message filter failures to strings.

Parameters:
[in]reason- The failure reason object
Returns:
a string explanation of the failure
template<typename T >
void RobotLocalization::RosFilter< T >::twistCallback ( const geometry_msgs::TwistWithCovarianceStamped::ConstPtr &  msg,
const CallbackData callbackData,
const std::string &  targetFrame 
)

Callback method for receiving all twist messages.

Parameters:
[in]msg- The ROS stamped twist with covariance message to take in.
[in]callbackData- Relevant static callback data
[in]targetFrame- The target frame_id into which to transform the data

Definition at line 1890 of file ros_filter.cpp.


Member Data Documentation

template<class T >
std::string RobotLocalization::RosFilter< T >::baseLinkFrameId_ [protected]

tf frame name for the robot's body frame

Definition at line 387 of file ros_filter.h.

template<class T >
ros::Subscriber RobotLocalization::RosFilter< T >::controlSub_ [protected]

Subscribes to the control input topic.

Definition at line 391 of file ros_filter.h.

template<class T >
std::ofstream RobotLocalization::RosFilter< T >::debugStream_ [protected]

Used for outputting debug messages.

Definition at line 409 of file ros_filter.h.

Used for updating the diagnostics.

Definition at line 417 of file ros_filter.h.

template<class T >
int RobotLocalization::RosFilter< T >::dynamicDiagErrorLevel_ [protected]

The max (worst) dynamic diagnostic level.

Definition at line 413 of file ros_filter.h.

template<class T >
std::map<std::string, std::string> RobotLocalization::RosFilter< T >::dynamicDiagnostics_ [protected]

This object accumulates dynamic diagnostics, e.g., diagnostics relating to sensor data.

The values are considered transient and are cleared at every iteration.

Definition at line 405 of file ros_filter.h.

template<class T >
T RobotLocalization::RosFilter< T >::filter_ [protected]

Our filter (EKF, UKF, etc.)

Definition at line 421 of file ros_filter.h.

An implicitly time ordered queue of past filter states used for smoothing.

Definition at line 598 of file ros_filter.h.

template<class T >
double RobotLocalization::RosFilter< T >::frequency_ [protected]

The frequency of the run loop.

Definition at line 425 of file ros_filter.h.

template<class T >
double RobotLocalization::RosFilter< T >::gravitationalAcc_ [protected]

What is the acceleration in Z due to gravity (m/s^2)? Default is +9.80665.

Definition at line 526 of file ros_filter.h.

template<class T >
double RobotLocalization::RosFilter< T >::historyLength_ [protected]

The depth of the history we track for smoothing/delayed measurement processing.

This is the guaranteed minimum buffer size for which previous states and measurements are kept.

Definition at line 431 of file ros_filter.h.

template<class T >
std::map<std::string, tf2::Transform> RobotLocalization::RosFilter< T >::initialMeasurements_ [protected]

Stores the first measurement from each topic for relative measurements.

When a given sensor is being integrated in relative mode, its first measurement is effectively treated as an offset, and future measurements have this first measurement removed before they are fused. This variable stores the initial measurements. Note that this is different from using differential mode, as in differential mode, pose data is converted to twist data, resulting in boundless error growth for the variables being fused. With relative measurements, the vehicle will start with a 0 heading and position, but the measurements are still fused absolutely.

Definition at line 459 of file ros_filter.h.

template<class T >
std::map<std::string, ros::Time> RobotLocalization::RosFilter< T >::lastMessageTimes_ [protected]

Store the last time a message from each topic was received.

If we're getting messages rapidly, we may accidentally get an older message arriving after a newer one. This variable keeps track of the most recent message time for each subscribed message topic. We also use it when listening to odometry messages to determine if we should be using messages from that topic.

Definition at line 469 of file ros_filter.h.

template<class T >
ros::Time RobotLocalization::RosFilter< T >::lastSetPoseTime_ [protected]

Store the last time set pose message was received.

If we receive a setPose message to reset the filter, we can get in strange situations wherein we process the pose reset, but then even after another spin cycle or two, we can get a new message with a time stamp that is *older* than the setPose message's time stamp. This means we have to check the message's time stamp against the lastSetPoseTime_.

Definition at line 478 of file ros_filter.h.

template<class T >
Eigen::VectorXd RobotLocalization::RosFilter< T >::latestControl_ [protected]

The most recent control input.

Definition at line 435 of file ros_filter.h.

template<class T >
ros::Time RobotLocalization::RosFilter< T >::latestControlTime_ [protected]

The time of the most recent control input.

Definition at line 439 of file ros_filter.h.

template<class T >
std::string RobotLocalization::RosFilter< T >::mapFrameId_ [protected]

tf frame name for the robot's map (world-fixed) frame

Definition at line 482 of file ros_filter.h.

A deque of previous measurements which is implicitly ordered from earliest to latest measurement.

Definition at line 604 of file ros_filter.h.

We process measurements by queueing them up in callbacks and processing them all at once within each iteration.

Definition at line 488 of file ros_filter.h.

template<class T >
ros::NodeHandle RobotLocalization::RosFilter< T >::nh_ [protected]

Node handle.

Definition at line 492 of file ros_filter.h.

template<class T >
ros::NodeHandle RobotLocalization::RosFilter< T >::nhLocal_ [protected]

Local node handle (for params)

Definition at line 496 of file ros_filter.h.

template<class T >
std::string RobotLocalization::RosFilter< T >::odomFrameId_ [protected]

tf frame name for the robot's odometry (world-fixed) frame

Definition at line 500 of file ros_filter.h.

template<class T >
std::map<std::string, Eigen::MatrixXd> RobotLocalization::RosFilter< T >::previousMeasurementCovariances_ [protected]

We also need the previous covariance matrix for differential data.

Definition at line 514 of file ros_filter.h.

template<class T >
std::map<std::string, tf2::Transform> RobotLocalization::RosFilter< T >::previousMeasurements_ [protected]

Stores the last measurement from a given topic for differential integration.

To carry out differential integration, we have to (1) transform that into the target frame (probably the frame specified by odomFrameId_), (2) "subtract" the previous measurement from the current measurement, and then (3) transform it again by the previous state estimate. This holds the measurements used for step (2).

Definition at line 510 of file ros_filter.h.

template<class T >
bool RobotLocalization::RosFilter< T >::printDiagnostics_ [protected]

Whether or not we print diagnostic messages to the /diagnostics topic.

Definition at line 518 of file ros_filter.h.

template<class T >
bool RobotLocalization::RosFilter< T >::publishAcceleration_ [protected]

Whether we publish the acceleration.

Definition at line 592 of file ros_filter.h.

template<class T >
bool RobotLocalization::RosFilter< T >::publishTransform_ [protected]

Whether we publish the transform from the world_frame to the base_link_frame.

Definition at line 588 of file ros_filter.h.

template<class T >
std::map<std::string, bool> RobotLocalization::RosFilter< T >::removeGravitationalAcc_ [protected]

If including acceleration for each IMU input, whether or not we remove acceleration due to gravity.

Definition at line 522 of file ros_filter.h.

template<class T >
ros::ServiceServer RobotLocalization::RosFilter< T >::setPoseSrv_ [protected]

Service that allows another node to change the current state and recieve a confirmation. Uses a custom SetPose service.

Definition at line 536 of file ros_filter.h.

template<class T >
ros::Subscriber RobotLocalization::RosFilter< T >::setPoseSub_ [protected]

Subscribes to the set_pose topic (usually published from rviz). Message type is geometry_msgs/PoseWithCovarianceStamped.

Definition at line 531 of file ros_filter.h.

template<class T >
bool RobotLocalization::RosFilter< T >::smoothLaggedData_ [protected]

Whether or not we use smoothing.

Definition at line 540 of file ros_filter.h.

template<class T >
std::vector<std::string> RobotLocalization::RosFilter< T >::stateVariableNames_ [protected]

Contains the state vector variable names in string format.

Definition at line 544 of file ros_filter.h.

template<class T >
int RobotLocalization::RosFilter< T >::staticDiagErrorLevel_ [protected]

The max (worst) static diagnostic level.

Definition at line 548 of file ros_filter.h.

template<class T >
std::map<std::string, std::string> RobotLocalization::RosFilter< T >::staticDiagnostics_ [protected]

This object accumulates static diagnostics, e.g., diagnostics relating to the configuration parameters.

The values are treated as static and always reported (i.e., this object is never cleared)

Definition at line 398 of file ros_filter.h.

template<class T >
tf2_ros::Buffer RobotLocalization::RosFilter< T >::tfBuffer_ [protected]

Transform buffer for managing coordinate transforms.

Definition at line 552 of file ros_filter.h.

Transform listener for receiving transforms.

Definition at line 556 of file ros_filter.h.

template<class T >
ros::Duration RobotLocalization::RosFilter< T >::tfTimeOffset_ [protected]

For future (or past) dating the world_frame->base_link_frame transform.

Definition at line 560 of file ros_filter.h.

template<class T >
ros::Duration RobotLocalization::RosFilter< T >::tfTimeout_ [protected]

Parameter that specifies the how long we wait for a transform to become available.

Definition at line 443 of file ros_filter.h.

template<class T >
std::vector<ros::Subscriber> RobotLocalization::RosFilter< T >::topicSubs_ [protected]

Vector to hold our subscribers until they go out of scope.

Definition at line 447 of file ros_filter.h.

template<class T >
bool RobotLocalization::RosFilter< T >::twoDMode_ [protected]

Whether or not we're in 2D mode.

If this is true, the filter binds all 3D variables (Z, roll, pitch, and their respective velocities) to 0 for every measurement.

Definition at line 568 of file ros_filter.h.

template<class T >
bool RobotLocalization::RosFilter< T >::useControl_ [protected]

Whether or not we use a control term.

Definition at line 572 of file ros_filter.h.

template<class T >
geometry_msgs::TransformStamped RobotLocalization::RosFilter< T >::worldBaseLinkTransMsg_ [protected]

Message that contains our latest transform (i.e., state)

We use the vehicle's latest state in a number of places, and often use it as a transform, so this is the most convenient variable to use as our global "current state" object

Definition at line 580 of file ros_filter.h.

template<class T >
std::string RobotLocalization::RosFilter< T >::worldFrameId_ [protected]

tf frame name that is the parent frame of the transform that this node will calculate and broadcast.

Definition at line 584 of file ros_filter.h.


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


robot_localization
Author(s): Tom Moore
autogenerated on Sun Apr 2 2017 03:39:46