40 int main(
int argc,
char** argv)
43 ros::init(argc, argv,
"rt_usb_9axisimu_driver");
45 std::string imu_port = std::string(
"/dev/ttyACM0");
47 std::string imu_frame_id = std::string(
"imu_link");
51 ros::param::get(
"~linear_acceleration_stddev", imu_stddev_linear_acceleration);
53 ros::param::get(
"~angular_velocity_stddev", imu_stddev_angular_velocity);
59 driver.
setImuStdDev(imu_stddev_linear_acceleration, imu_stddev_angular_velocity, imu_stddev_magnetic_field);
70 ROS_INFO(
"Format check has completed.");
81 ROS_ERROR(
"Data format is neither binary nor ascii.");
98 ROS_ERROR(
"readSensorData() returns false, please check your devices.\n");
106 ROS_ERROR(
"Error opening sensor device, please re-check your devices.\n");
109 ROS_INFO(
"Shutting down RT imu driver complete.\n");
const double DEFAULT_ANGULAR_VELOCITY_STDDEV
bool hasRefreshedImuData(void)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool hasBinaryDataFormat(void)
const double DEFAULT_LINEAR_ACCELERATION_STDDEV
const double DEFAULT_MAGNETIC_FIELD_STDDEV
void stopCommunication(void)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
void setImuStdDev(double linear_acceleration, double angular_velocity, double magnetic_field)
int main(int argc, char **argv)
bool hasAsciiDataFormat(void)
bool startCommunication()
bool hasCompletedFormatCheck(void)
void setImuFrameIdName(std::string frame_id)
void checkDataFormat(void)