#include <rawlog_record_node.h>
Public Member Functions | |
void | callbackParameters (mrpt_rawlog::MotionConfig &config, uint32_t level) |
ParametersNode () | |
void | update (const unsigned long &loop_count) |
Public Attributes | |
std::string | base_frame_id |
ros::NodeHandle | node |
std::string | odom_frame_id |
int | parameter_update_skip |
double | rate |
dynamic_reconfigure::Server < mrpt_rawlog::MotionConfig > ::CallbackType | reconfigureFnc_ |
dynamic_reconfigure::Server < mrpt_rawlog::MotionConfig > | reconfigureServer_ |
std::string | tf_prefix |
Static Public Attributes | |
static const int | MOTION_MODEL_GAUSSIAN = 0 |
static const int | MOTION_MODEL_THRUN = 1 |
Definition at line 44 of file rawlog_record_node.h.
Definition at line 32 of file rawlog_record_node_parameters.cpp.
void RawlogRecordNode::ParametersNode::callbackParameters | ( | mrpt_rawlog::MotionConfig & | config, |
uint32_t | level | ||
) |
Definition at line 56 of file rawlog_record_node_parameters.cpp.
void RawlogRecordNode::ParametersNode::update | ( | const unsigned long & | loop_count | ) |
Definition at line 50 of file rawlog_record_node_parameters.cpp.
std::string RawlogRecordNode::ParametersNode::base_frame_id |
Definition at line 57 of file rawlog_record_node.h.
const int RawlogRecordNode::ParametersNode::MOTION_MODEL_GAUSSIAN = 0 [static] |
Definition at line 45 of file rawlog_record_node.h.
const int RawlogRecordNode::ParametersNode::MOTION_MODEL_THRUN = 1 [static] |
Definition at line 46 of file rawlog_record_node.h.
Definition at line 48 of file rawlog_record_node.h.
std::string RawlogRecordNode::ParametersNode::odom_frame_id |
Definition at line 56 of file rawlog_record_node.h.
Definition at line 54 of file rawlog_record_node.h.
Definition at line 53 of file rawlog_record_node.h.
dynamic_reconfigure::Server<mrpt_rawlog::MotionConfig>::CallbackType RawlogRecordNode::ParametersNode::reconfigureFnc_ |
Definition at line 51 of file rawlog_record_node.h.
dynamic_reconfigure::Server<mrpt_rawlog::MotionConfig> RawlogRecordNode::ParametersNode::reconfigureServer_ |
Definition at line 50 of file rawlog_record_node.h.
std::string RawlogRecordNode::ParametersNode::tf_prefix |
Definition at line 55 of file rawlog_record_node.h.