#include <rawlog_record_node.h>
Public Member Functions | |
void | callbackParameters (mrpt_rawlog::RawLogRecordConfig &config, uint32_t level) |
ParametersNode (RawlogRecord::Parameters &base_params) | |
void | update (const unsigned long &loop_count) |
Public Attributes | |
std::string | base_frame_id |
RawlogRecord::Parameters & | base_param_ |
ros::NodeHandle | node |
std::string | odom_frame_id |
int | parameter_update_skip |
double | rate |
dynamic_reconfigure::Server < mrpt_rawlog::RawLogRecordConfig > ::CallbackType | reconfigureFnc_ |
dynamic_reconfigure::Server < mrpt_rawlog::RawLogRecordConfig > | reconfigureServer_ |
double | sensor_frame_sync_threshold |
std::string | tf_prefix |
Static Public Attributes | |
static const int | MOTION_MODEL_GAUSSIAN = 0 |
static const int | MOTION_MODEL_THRUN = 1 |
Definition at line 52 of file rawlog_record_node.h.
RawlogRecordNode::ParametersNode::ParametersNode | ( | RawlogRecord::Parameters & | base_params | ) |
Definition at line 40 of file rawlog_record_node_parameters.cpp.
void RawlogRecordNode::ParametersNode::callbackParameters | ( | mrpt_rawlog::RawLogRecordConfig & | config, |
uint32_t | level | ||
) |
Definition at line 88 of file rawlog_record_node_parameters.cpp.
void RawlogRecordNode::ParametersNode::update | ( | const unsigned long & | loop_count | ) |
Definition at line 80 of file rawlog_record_node_parameters.cpp.
std::string RawlogRecordNode::ParametersNode::base_frame_id |
Definition at line 70 of file rawlog_record_node.h.
Definition at line 58 of file rawlog_record_node.h.
const int RawlogRecordNode::ParametersNode::MOTION_MODEL_GAUSSIAN = 0 [static] |
Definition at line 54 of file rawlog_record_node.h.
const int RawlogRecordNode::ParametersNode::MOTION_MODEL_THRUN = 1 [static] |
Definition at line 55 of file rawlog_record_node.h.
Definition at line 57 of file rawlog_record_node.h.
std::string RawlogRecordNode::ParametersNode::odom_frame_id |
Definition at line 69 of file rawlog_record_node.h.
Definition at line 67 of file rawlog_record_node.h.
Definition at line 66 of file rawlog_record_node.h.
dynamic_reconfigure::Server< mrpt_rawlog::RawLogRecordConfig>::CallbackType RawlogRecordNode::ParametersNode::reconfigureFnc_ |
Definition at line 64 of file rawlog_record_node.h.
dynamic_reconfigure::Server<mrpt_rawlog::RawLogRecordConfig> RawlogRecordNode::ParametersNode::reconfigureServer_ |
Definition at line 62 of file rawlog_record_node.h.
Definition at line 71 of file rawlog_record_node.h.
std::string RawlogRecordNode::ParametersNode::tf_prefix |
Definition at line 68 of file rawlog_record_node.h.