Skip to content
Snippets Groups Projects
Commit 11cfb373 authored by Sergi Hernandez's avatar Sergi Hernandez
Browse files

Chnaged the driver state to change the rate and operational mode from CLOSE to STOP.

Not calibrated messages as DEBUG.
parent 0d96c67e
No related branches found
No related tags found
1 merge request!1Kinetic migration
...@@ -54,12 +54,12 @@ gen.const("ndof", int_t, 12, "ndof") ...@@ -54,12 +54,12 @@ gen.const("ndof", int_t, 12, "ndof")
], "Possible operation modes.") ], "Possible operation modes.")
# Name Type Reconfiguration level Description Default Min Max # 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("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("cal_filename", str_t, SensorLevels.RECONFIGURE_STOP, "Sensor calibration data", "")
gen.add("tf_prefix", str_t, SensorLevels.RECONFIGURE_STOP, "TF prefix", "") 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("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) #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")) exit(gen.generate(PACKAGE, "Bno055ImuDriver", "Bno055Imu"))
...@@ -57,7 +57,6 @@ bool Bno055ImuDriver::startDriver(void) ...@@ -57,7 +57,6 @@ bool Bno055ImuDriver::startDriver(void)
this->imu_device->load_calibration(this->config_.cal_filename); 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_operation_mode((op_mode_t)this->config_.mode);
this->imu_device->set_data_rate(this->config_.update_rate); this->imu_device->set_data_rate(this->config_.update_rate);
ROS_INFO("IMU successfully started");
this->unlock(); this->unlock();
return true; return true;
}catch(CException &e){ }catch(CException &e){
...@@ -72,7 +71,6 @@ bool Bno055ImuDriver::startDriver(void) ...@@ -72,7 +71,6 @@ bool Bno055ImuDriver::startDriver(void)
this->imu_device->set_operation_mode(config_mode); this->imu_device->set_operation_mode(config_mode);
this->imu_device->set_data_rate(this->config_.update_rate); this->imu_device->set_data_rate(this->config_.update_rate);
this->imu_device->set_operation_mode((op_mode_t)this->config_.mode); this->imu_device->set_operation_mode((op_mode_t)this->config_.mode);
ROS_INFO("IMU successfully started");
this->unlock(); this->unlock();
return true; return true;
}catch(CException &e){ }catch(CException &e){
...@@ -108,10 +106,11 @@ void Bno055ImuDriver::config_update(Config& new_cfg, uint32_t level) ...@@ -108,10 +106,11 @@ void Bno055ImuDriver::config_update(Config& new_cfg, uint32_t level)
switch(this->getState()) switch(this->getState())
{ {
case iri_base_driver::CLOSED: case iri_base_driver::CLOSED:
this->frame_id=new_cfg.tf_prefix+"/"+new_cfg.frame_id;
break; break;
case iri_base_driver::OPENED: 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; break;
case iri_base_driver::RUNNING: case iri_base_driver::RUNNING:
...@@ -206,11 +205,11 @@ bool Bno055ImuDriver::is_imu_calibrated(void) ...@@ -206,11 +205,11 @@ bool Bno055ImuDriver::is_imu_calibrated(void)
else else
{ {
if(!accel_cal) 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) if(!mag_cal)
ROS_WARN("Magnetometer no calibrated: Move the sensor randomly"); ROS_DEBUG("Magnetometer no calibrated: Move the sensor randomly");
if(!gyro_cal) 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; return false;
} }
}catch(CException &e){ }catch(CException &e){
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment