diff --git a/cfg/Bno055Imu.cfg b/cfg/Bno055Imu.cfg index d21d2bee24856766969c5e18497df90b9334196a..d8fb52ac510864cde06106250cd50d7e5684ad15 100755 --- a/cfg/Bno055Imu.cfg +++ b/cfg/Bno055Imu.cfg @@ -54,12 +54,12 @@ gen.const("ndof", int_t, 12, "ndof") ], "Possible operation modes.") # Name Type Reconfiguration level Description Default Min Max -gen.add("update_rate", double_t, SensorLevels.RECONFIGURE_CLOSE, "Data update rate in Hz", 20.0, 1.0, 100.0) +gen.add("update_rate", double_t, SensorLevels.RECONFIGURE_STOP, "Data update rate in Hz", 20.0, 1.0, 100.0) gen.add("serial_device", str_t, SensorLevels.RECONFIGURE_CLOSE, "Device serial port", "/dev/ttyUSB1") gen.add("cal_filename", str_t, SensorLevels.RECONFIGURE_STOP, "Sensor calibration data", "") gen.add("tf_prefix", str_t, SensorLevels.RECONFIGURE_STOP, "TF prefix", "") gen.add("frame_id", str_t, SensorLevels.RECONFIGURE_STOP, "IMU frame_id in the urdf file", "") -gen.add("mode", int_t, SensorLevels.RECONFIGURE_CLOSE, "Operation mode", 12, 1, 12, edit_method=enum_operation_mode) +gen.add("mode", int_t, SensorLevels.RECONFIGURE_STOP, "Operation mode", 12, 1, 12, edit_method=enum_operation_mode) #gen.add("velocity_scale_factor", double_t, SensorLevels.RECONFIGURE_STOP, "Maximum velocity scale factor", 0.5, 0.0, 1.0) exit(gen.generate(PACKAGE, "Bno055ImuDriver", "Bno055Imu")) diff --git a/src/bno055_imu_ros_driver.cpp b/src/bno055_imu_ros_driver.cpp index e232e127de336cab87acf2e990d0d5caace948a4..f1852fcc4fba8190d6c4f34d7f81ed7573525b34 100644 --- a/src/bno055_imu_ros_driver.cpp +++ b/src/bno055_imu_ros_driver.cpp @@ -57,7 +57,6 @@ bool Bno055ImuDriver::startDriver(void) this->imu_device->load_calibration(this->config_.cal_filename); this->imu_device->set_operation_mode((op_mode_t)this->config_.mode); this->imu_device->set_data_rate(this->config_.update_rate); - ROS_INFO("IMU successfully started"); this->unlock(); return true; }catch(CException &e){ @@ -72,7 +71,6 @@ bool Bno055ImuDriver::startDriver(void) this->imu_device->set_operation_mode(config_mode); this->imu_device->set_data_rate(this->config_.update_rate); this->imu_device->set_operation_mode((op_mode_t)this->config_.mode); - ROS_INFO("IMU successfully started"); this->unlock(); return true; }catch(CException &e){ @@ -108,10 +106,11 @@ void Bno055ImuDriver::config_update(Config& new_cfg, uint32_t level) switch(this->getState()) { case iri_base_driver::CLOSED: - this->frame_id=new_cfg.tf_prefix+"/"+new_cfg.frame_id; break; case iri_base_driver::OPENED: + this->imu_device->set_data_rate(new_cfg.update_rate); + this->frame_id=new_cfg.tf_prefix+"/"+new_cfg.frame_id; break; case iri_base_driver::RUNNING: @@ -206,11 +205,11 @@ bool Bno055ImuDriver::is_imu_calibrated(void) else { if(!accel_cal) - ROS_WARN("Accelerometer not calibrated: Move the sensor slowly to six different positions and hold it steady for a few seconds"); + ROS_DEBUG("Accelerometer not calibrated: Move the sensor slowly to six different positions and hold it steady for a few seconds"); if(!mag_cal) - ROS_WARN("Magnetometer no calibrated: Move the sensor randomly"); + ROS_DEBUG("Magnetometer no calibrated: Move the sensor randomly"); if(!gyro_cal) - ROS_WARN("Gyroscope not calibrated: Hold the sensor steady at any position for a few seconds"); + ROS_DEBUG("Gyroscope not calibrated: Hold the sensor steady at any position for a few seconds"); return false; } }catch(CException &e){