#include <orientation_filter.h>
Public Member Functions | |
OrientationFilter () | |
Calculates the roll and pitch of the base and the pitch of the sensor tower from CARL's IMUs. | |
Private Member Functions | |
void | baseImuCallback (const sensor_msgs::Imu::ConstPtr &data) |
void | topImuCallback (const sensor_msgs::Imu::ConstPtr &data) |
Private Attributes | |
ros::Subscriber | baseImuSubscriber |
bool | baseOrientationInitialized |
ros::Publisher | frameJointStatePublisher |
sensor_msgs::JointState | jointStates |
ros::NodeHandle | n |
bool | output |
float | PPrev [2] |
float | PPrevTop |
ros::Time | prevUpdateTime |
ros::Time | prevUpdateTimeTop |
ros::Subscriber | topImuSubscriber |
Definition at line 27 of file orientation_filter.h.
Calculates the roll and pitch of the base and the pitch of the sensor tower from CARL's IMUs.
Constructor
.cpp orientation_filter creates a ROS node that measures orientations for the base and sensor tower by combining and filtering accelerometer and gyro data.
Definition at line 14 of file orientation_filter.cpp.
void OrientationFilter::baseImuCallback | ( | const sensor_msgs::Imu::ConstPtr & | data | ) | [private] |
Base IMU callback.
data | data from the base IMU |
Definition at line 103 of file orientation_filter.cpp.
void OrientationFilter::topImuCallback | ( | const sensor_msgs::Imu::ConstPtr & | data | ) | [private] |
Top IMU callback.
data | data from the top IMU |
Definition at line 41 of file orientation_filter.cpp.
Subscriber for data from the base IMU
Definition at line 53 of file orientation_filter.h.
bool OrientationFilter::baseOrientationInitialized [private] |
Definition at line 57 of file orientation_filter.h.
joint state publisher for various parts of CARL's frame
Definition at line 52 of file orientation_filter.h.
sensor_msgs::JointState OrientationFilter::jointStates [private] |
Definition at line 56 of file orientation_filter.h.
ros::NodeHandle OrientationFilter::n [private] |
Definition at line 50 of file orientation_filter.h.
bool OrientationFilter::output [private] |
Definition at line 58 of file orientation_filter.h.
float OrientationFilter::PPrev[2] [private] |
Definition at line 62 of file orientation_filter.h.
float OrientationFilter::PPrevTop [private] |
Definition at line 61 of file orientation_filter.h.
ros::Time OrientationFilter::prevUpdateTime [private] |
Definition at line 60 of file orientation_filter.h.
Definition at line 59 of file orientation_filter.h.
Subscriber for data from the top IMU
Definition at line 54 of file orientation_filter.h.