|
| MSCEqFRos (const ros::NodeHandle &nh, const std::string &msceqf_config_filepath, const std::string &imu_topic, const std::string &cam_topic, const std::string &pose_topic, const std::string &path_topic, const std::string &image_topic, const std::string &extrinsics_topic, const std::string &intrinsics_topic, const std::string &origin_topic, const bool &record, const std::string &bagfile) |
| Constructor.
|
|
void | callback_image (const sensor_msgs::Image::ConstPtr &msg) |
| Image callback.
|
|
void | callback_imu (const sensor_msgs::Imu::ConstPtr &msg) |
| IMU callback.
|
|
◆ MSCEqFRos()
MSCEqFRos::MSCEqFRos |
( |
const ros::NodeHandle & | nh, |
|
|
const std::string & | msceqf_config_filepath, |
|
|
const std::string & | imu_topic, |
|
|
const std::string & | cam_topic, |
|
|
const std::string & | pose_topic, |
|
|
const std::string & | path_topic, |
|
|
const std::string & | image_topic, |
|
|
const std::string & | extrinsics_topic, |
|
|
const std::string & | intrinsics_topic, |
|
|
const std::string & | origin_topic, |
|
|
const bool & | record, |
|
|
const std::string & | bagfile ) |
Constructor.
- Parameters
-
Ros | ROS node handle |
msceqf_config_filepath | Path of configuration yaml file for the msceqf |
imu_topic | IMU topic |
cam_topic | Camera topic |
pose_topic | Pose topic |
path_topic | Path topic |
image_topic | Image topic |
extrinsics_topic | Extrinsics topic |
intrinsics_topic | Intrinsics topic |
record | Flag to decide wether record a bagfile or not |
bagfile | Bagfile name |
◆ callback_image()
void MSCEqFRos::callback_image |
( |
const sensor_msgs::Image::ConstPtr & | msg | ) |
|
Image callback.
- Parameters
-
Message | message constant pointer |
◆ callback_imu()
void MSCEqFRos::callback_imu |
( |
const sensor_msgs::Imu::ConstPtr & | msg | ) |
|
IMU callback.
- Parameters
-
Message | message constant pointer |
The documentation for this class was generated from the following file: