Functions | Variables
odometry_provider.cpp File Reference
#include <ros/ros.h>
#include <sensor_msgs/JointState.h>
#include <nav_msgs/Odometry.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <tf/transform_listener.h>
#include <string>
#include <utility>
#include <math.h>
Include dependency graph for odometry_provider.cpp:

Go to the source code of this file.

Functions

double getAngularVel (const double old_steps, const double new_steps, const bool dir, const double dt)
 Calculates angular velocity from old and new angle on joint.
double getYaw (const double velRight, const double velLeft)
int main (int argc, char **argv)
void odomData_cb (const sensor_msgs::JointState::ConstPtr &left_motor_msg, const sensor_msgs::JointState::ConstPtr &right_motor_msg)
void setWheelSpacing (const std::string &motor_left_frame, const std::string &motor_right_frame)

Variables

bool dir_left = true
bool dir_right = true
ros::Time last_time
double left_angular = 0
double left_steps = -5
std::string odom_frame_id = "/odom"
std::string odom_left_wheel = "hal/leftMotor/getState"
std::string odom_publish_topic = "odom"
std::string odom_right_wheel = "hal/rightMotor/getState"
double pos_th = 0
double pos_x = 0
double pos_y = 0
ros::Publisher publisher
double right_angular = 0
double right_steps = -5
std::string tf_prefix
double WHEEL_RADIUS = 0.098
double WHEELS_HALF_SPACING = 0.15

Function Documentation

double getAngularVel ( const double  old_steps,
const double  new_steps,
const bool  dir,
const double  dt 
)

Calculates angular velocity from old and new angle on joint.

Parameters:
[in]old_steps- angle on joint in previous iteration
[in]new_steps- current angle on joint
[in]dir- direction of rotation true=forward, false = backward
[in]dt- time elapsed between measurement of old_steps and new_steps
Returns:
Current angular velocity on the joint

Definition at line 74 of file odometry_provider.cpp.

double getYaw ( const double  velRight,
const double  velLeft 
)

Definition at line 43 of file odometry_provider.cpp.

int main ( int  argc,
char **  argv 
)

Definition at line 151 of file odometry_provider.cpp.

void odomData_cb ( const sensor_msgs::JointState::ConstPtr &  left_motor_msg,
const sensor_msgs::JointState::ConstPtr &  right_motor_msg 
)

Definition at line 85 of file odometry_provider.cpp.

void setWheelSpacing ( const std::string &  motor_left_frame,
const std::string &  motor_right_frame 
)

Definition at line 47 of file odometry_provider.cpp.


Variable Documentation

bool dir_left = true

Definition at line 30 of file odometry_provider.cpp.

bool dir_right = true

Definition at line 31 of file odometry_provider.cpp.

Definition at line 32 of file odometry_provider.cpp.

double left_angular = 0

Definition at line 34 of file odometry_provider.cpp.

double left_steps = -5

Definition at line 28 of file odometry_provider.cpp.

std::string odom_frame_id = "/odom"

Definition at line 37 of file odometry_provider.cpp.

std::string odom_left_wheel = "hal/leftMotor/getState"

Definition at line 40 of file odometry_provider.cpp.

std::string odom_publish_topic = "odom"

Definition at line 38 of file odometry_provider.cpp.

std::string odom_right_wheel = "hal/rightMotor/getState"

Definition at line 39 of file odometry_provider.cpp.

double pos_th = 0

Definition at line 27 of file odometry_provider.cpp.

double pos_x = 0

Definition at line 25 of file odometry_provider.cpp.

double pos_y = 0

Definition at line 26 of file odometry_provider.cpp.

Definition at line 20 of file odometry_provider.cpp.

double right_angular = 0

Definition at line 35 of file odometry_provider.cpp.

double right_steps = -5

Definition at line 29 of file odometry_provider.cpp.

std::string tf_prefix

Definition at line 17 of file odometry_provider.cpp.

double WHEEL_RADIUS = 0.098

Definition at line 23 of file odometry_provider.cpp.

double WHEELS_HALF_SPACING = 0.15

Definition at line 22 of file odometry_provider.cpp.



p3dx_dpl
Author(s):
autogenerated on Sat Jun 8 2019 20:22:37