Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
LaserTransform Class Reference

#include <laser_transform_core.h>

List of all members.

Public Member Functions

void callbackOdometryFiltered (const nav_msgs::Odometry::ConstPtr &msg)
 Callcack function for filtered odometry.
void callbackPcl (const sensor_msgs::PointCloud2::ConstPtr &msg)
 Callcack function for laser scanner pcl.
void checkConvergenceSpeed ()
 Set the speed of convergence depends on the angular velocity.
void clearOctomap (ros::ServiceClient *client)
 Set the unnecessary part of the octomap free.
int init ()
 Init.
 LaserTransform ()
 Constructur.
void publishImuMessage (ros::Publisher *pub_message)
 Publish the IMU message.
void publishMagneticFieldMessage (ros::Publisher *pub_message)
 Publish the MagneticField message.
void publishNavSatFixMessage (ros::Publisher *pub_message)
 Publish the NavSatFix message.
void publishOdometryMessage (ros::Publisher *pub_message)
 Publish the current car velocity.
void publishPclMessage (ros::Publisher *pub_message)
 Publish the transformed plc data.
int setImuConvergenceSpeed (uint16_t imu_convergence_speed)
 IMU convergence_speed setter.
void setLaserPose (double x, double y, double z, double yaw, double pitch, double roll)
 Set the laser pose.
void setPclPublisher (ros::Publisher *pub)
 Set publisher for transformed pcl data.
 ~LaserTransform ()
 Destructor.

Private Member Functions

float deg2rad (float x)
 Calculate rad from deg.
int getPosition (float *x_pos, float *y_pos, float *z_pos)
 Get current car position.
tf::Quaternion getQuaternion ()
 Get IMU quaternion.
float rad2deg (float x)
 Calculate deg from rad.

Static Private Member Functions

static void callbackConnected (uint8_t connect_reason, void *user_data)
 Callback function for Tinkerforge ip connected .
static void callbackDb (uint8_t button_l, uint8_t button_r, uint8_t led_l, uint8_t led_r, void *user_data)
 Callback function for Tinkerforge Dual Button Bricklet.
static void callbackEnumerate (const char *uid, const char *connected_uid, char position, uint8_t hardware_version[3], uint8_t firmware_version[3], uint16_t device_identifier, uint8_t enumeration_type, void *user_data)
 Callback function for Tinkerforge enumerate.
static void callbackIdi4 (uint8_t interrupt_mask, uint8_t value_mask, void *user_data)
 Callback function for Tinkerforge Industrial Digital In 4 Bricklet.

Private Attributes

float course_gps
 The GPS course.
DualButton db
 The DualButton device.
std::fstream full_log
 Full-Logfile.
GPS gps
 The GPS device.
std::fstream gps_log
 GPS-Logfile.
IndustrialDigitalIn4 idi4
 The IndustrialDual020mA device.
IMU imu
 The IMU device.
int imu_convergence_speed
 The IMU convergence_speed.
ros::Time imu_init_time
 Time to correct the imu orientation.
IMUV2 imu_v2
 The IMU_v2 device.
IPConnection ipcon
 IP connection to Tinkerforge deamon.
bool is_gps_connected
 The GPS state.
bool is_idi4_connected
 The IndustrialDual020mA state.
bool is_imu_connected
 The IMU state.
bool is_imu_v2_connected
 The IMU_v2 state.
bool isMeasure
 Flag for active velocity measurement.
bool isPlc
 laser scanner orientation
tf::Transform laser_pose
 laser scanner pose
ros::Time last_rev
 Time since the last rev.
bool new_pcl_filtered
 Flag for new raw pcl available.
sensor_msgs::PointCloud2 pcl_out
 The transformed point cloud.
ros::Publisherpcl_pub
 Publisher for transfered pcl data.
bool publish_new_pcl
 Flag for new transformed pcl available.
float rev
 The rev from the inductive proximity switch sensor.
uint16_t rpm_cnt
 Counter for rounds per second (na)
double start_latitude
 start latitude
double start_longitude
 start longitude
std::fstream velo_log
 Velocity-Logfile.
float velocity
 The current vehicle velocity.
float velocity_gps
 The current vehicle velocity.
float xpos
 The current car position on x-axis.
float ypos
 The current car position on y-axis.
float yy

Detailed Description

Definition at line 21 of file laser_transform_core.h.


Constructor & Destructor Documentation

Constructur.

Definition at line 44 of file laser_transform_core.cpp.

Destructor.

Definition at line 98 of file laser_transform_core.cpp.


Member Function Documentation

void LaserTransform::callbackConnected ( uint8_t  connect_reason,
void *  user_data 
) [static, private]

Callback function for Tinkerforge ip connected .

Definition at line 518 of file laser_transform_core.cpp.

void LaserTransform::callbackDb ( uint8_t  button_l,
uint8_t  button_r,
uint8_t  led_l,
uint8_t  led_r,
void *  user_data 
) [static, private]

Callback function for Tinkerforge Dual Button Bricklet.

Definition at line 666 of file laser_transform_core.cpp.

void LaserTransform::callbackEnumerate ( const char *  uid,
const char *  connected_uid,
char  position,
uint8_t  hardware_version[3],
uint8_t  firmware_version[3],
uint16_t  device_identifier,
uint8_t  enumeration_type,
void *  user_data 
) [static, private]

Callback function for Tinkerforge enumerate.

Definition at line 531 of file laser_transform_core.cpp.

void LaserTransform::callbackIdi4 ( uint8_t  interrupt_mask,
uint8_t  value_mask,
void *  user_data 
) [static, private]

Callback function for Tinkerforge Industrial Digital In 4 Bricklet.

Definition at line 611 of file laser_transform_core.cpp.

void LaserTransform::callbackOdometryFiltered ( const nav_msgs::Odometry::ConstPtr &  msg)

Callcack function for filtered odometry.

Definition at line 487 of file laser_transform_core.cpp.

void LaserTransform::callbackPcl ( const sensor_msgs::PointCloud2::ConstPtr &  msg)

Callcack function for laser scanner pcl.

Definition at line 473 of file laser_transform_core.cpp.

Set the speed of convergence depends on the angular velocity.

Definition at line 294 of file laser_transform_core.cpp.

Set the unnecessary part of the octomap free.

Definition at line 851 of file laser_transform_core.cpp.

float LaserTransform::deg2rad ( float  x) [inline, private]

Calculate rad from deg.

Definition at line 106 of file laser_transform_core.h.

int LaserTransform::getPosition ( float *  x_pos,
float *  y_pos,
float *  z_pos 
) [private]

Get current car position.

Definition at line 949 of file laser_transform_core.cpp.

Get IMU quaternion.

Definition at line 707 of file laser_transform_core.cpp.

Init.

Definition at line 137 of file laser_transform_core.cpp.

Publish the IMU message.

Definition at line 182 of file laser_transform_core.cpp.

Publish the MagneticField message.

Definition at line 318 of file laser_transform_core.cpp.

Publish the NavSatFix message.

Definition at line 374 of file laser_transform_core.cpp.

Publish the current car velocity.

Definition at line 739 of file laser_transform_core.cpp.

Publish the transformed plc data.

Definition at line 168 of file laser_transform_core.cpp.

float LaserTransform::rad2deg ( float  x) [inline, private]

Calculate deg from rad.

Definition at line 100 of file laser_transform_core.h.

int LaserTransform::setImuConvergenceSpeed ( uint16_t  imu_convergence_speed) [inline]

IMU convergence_speed setter.

Definition at line 70 of file laser_transform_core.h.

void LaserTransform::setLaserPose ( double  x,
double  y,
double  z,
double  yaw,
double  pitch,
double  roll 
)

Set the laser pose.

Definition at line 822 of file laser_transform_core.cpp.

Set publisher for transformed pcl data.

Definition at line 64 of file laser_transform_core.h.


Member Data Documentation

float LaserTransform::course_gps [private]

The GPS course.

Definition at line 170 of file laser_transform_core.h.

The DualButton device.

Definition at line 138 of file laser_transform_core.h.

std::fstream LaserTransform::full_log [private]

Full-Logfile.

Definition at line 177 of file laser_transform_core.h.

The GPS device.

Definition at line 128 of file laser_transform_core.h.

std::fstream LaserTransform::gps_log [private]

GPS-Logfile.

Definition at line 173 of file laser_transform_core.h.

The IndustrialDual020mA device.

Definition at line 132 of file laser_transform_core.h.

The IMU device.

Definition at line 116 of file laser_transform_core.h.

The IMU convergence_speed.

Definition at line 120 of file laser_transform_core.h.

Time to correct the imu orientation.

Definition at line 122 of file laser_transform_core.h.

The IMU_v2 device.

Definition at line 124 of file laser_transform_core.h.

IP connection to Tinkerforge deamon.

Definition at line 114 of file laser_transform_core.h.

The GPS state.

Definition at line 130 of file laser_transform_core.h.

The IndustrialDual020mA state.

Definition at line 136 of file laser_transform_core.h.

The IMU state.

Definition at line 118 of file laser_transform_core.h.

The IMU_v2 state.

Definition at line 126 of file laser_transform_core.h.

bool LaserTransform::isMeasure [private]

Flag for active velocity measurement.

Definition at line 140 of file laser_transform_core.h.

bool LaserTransform::isPlc [private]

laser scanner orientation

Definition at line 160 of file laser_transform_core.h.

laser scanner pose

Definition at line 156 of file laser_transform_core.h.

Time since the last rev.

Definition at line 144 of file laser_transform_core.h.

Flag for new raw pcl available.

Definition at line 150 of file laser_transform_core.h.

sensor_msgs::PointCloud2 LaserTransform::pcl_out [private]

The transformed point cloud.

Definition at line 146 of file laser_transform_core.h.

Publisher for transfered pcl data.

Definition at line 112 of file laser_transform_core.h.

Flag for new transformed pcl available.

Definition at line 148 of file laser_transform_core.h.

float LaserTransform::rev [private]

The rev from the inductive proximity switch sensor.

Definition at line 142 of file laser_transform_core.h.

uint16_t LaserTransform::rpm_cnt [private]

Counter for rounds per second (na)

Definition at line 134 of file laser_transform_core.h.

start latitude

Definition at line 152 of file laser_transform_core.h.

start longitude

Definition at line 154 of file laser_transform_core.h.

std::fstream LaserTransform::velo_log [private]

Velocity-Logfile.

Definition at line 175 of file laser_transform_core.h.

float LaserTransform::velocity [private]

The current vehicle velocity.

Definition at line 166 of file laser_transform_core.h.

The current vehicle velocity.

Definition at line 168 of file laser_transform_core.h.

float LaserTransform::xpos [private]

The current car position on x-axis.

Definition at line 162 of file laser_transform_core.h.

float LaserTransform::ypos [private]

The current car position on y-axis.

Definition at line 164 of file laser_transform_core.h.

float LaserTransform::yy [private]

Definition at line 171 of file laser_transform_core.h.


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


tinkerforge_laser_transform
Author(s): M.Fischer
autogenerated on Thu Jun 6 2019 20:39:26