00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041 #include "MTi/MTi.h"
00042 #include <ros/ros.h>
00043
00044
00052 int main(int argc, char** argv)
00053 {
00054 ros::init(argc, argv, "mti_node");
00055 ros::NodeHandle pn("~");
00056
00057
00058 std::string portname;
00059 int baudrate;
00060 std::string frame_id;
00061 pn.param<std::string>("port", portname, "/dev/ttyUSB0");
00062 pn.param("baudrate", baudrate, 115200);
00063 pn.param<std::string>("frame_id", frame_id, Xsens::IMU_FRAME_ID);
00064
00065 Xsens::MTi::outputMode outputMode;
00066 pn.param<bool>("temperature", outputMode.temperatureData,false);
00067 pn.param<bool>("calibrated", outputMode.calibratedData,true);
00068 pn.param<bool>("orientation", outputMode.orientationData,true);
00069 pn.param<bool>("auxiliary", outputMode.auxiliaryData,false);
00070 pn.param<bool>("position", outputMode.positionData,false);
00071 pn.param<bool>("velocity", outputMode.velocityData,false);
00072 pn.param<bool>("status", outputMode.statusData,false);
00073 pn.param<bool>("rawGPS", outputMode.rawGPSData,false);
00074 pn.param<bool>("rawInertial", outputMode.rawInertialData,false);
00075
00076 Xsens::MTi::outputSettings outputSettings;
00077 pn.param<bool>("timeStamp", outputSettings.timeStamp,false);
00078 int orientationMode;
00079 pn.param<int>("orientationMode", orientationMode,Xsens::Quaternion);
00080 outputSettings.orientationMode = (Xsens::MTOrientationMode)orientationMode;
00081 pn.param<bool>("enableAcceleration", outputSettings.enableAcceleration,false);
00082 pn.param<bool>("enableRateOfTurn", outputSettings.enableRateOfTurn,false);
00083 pn.param<bool>("enableMagnetometer", outputSettings.enableMagnetometer,false);
00084 pn.param<bool>("velocityModeNED", outputSettings.velocityModeNED,false);
00085
00086 int scenarioAsInt;
00087 pn.param<int>("scenario",scenarioAsInt,Xsens::Automotive);
00088 Xsens::Scenario scenario = (Xsens::Scenario)scenarioAsInt;
00089 double GPSLeverArm_X, GPSLeverArm_Y, GPSLeverArm_Z;
00090 pn.param<double>("GPSLeverArm_X",GPSLeverArm_X,0.0);
00091 pn.param<double>("GPSLeverArm_Y",GPSLeverArm_Y,0.0);
00092 pn.param<double>("GPSLeverArm_Z",GPSLeverArm_Z,0.0);
00093 Xsens::MTi::Position GPS_lever_arm;
00094 GPS_lever_arm.x = GPSLeverArm_X;
00095 GPS_lever_arm.y = GPSLeverArm_Y;
00096 GPS_lever_arm.z = GPSLeverArm_Z;
00097
00098 Xsens::MTi * mti = new Xsens::MTi();
00099
00100 if(!mti->openPort((char*)portname.c_str(), baudrate))
00101 {
00102 ROS_FATAL("MTi -- Unable to connect to the MTi.");
00103 ROS_BREAK();
00104 }
00105 ROS_INFO("MTi -- Successfully connected to the MTi!");
00106
00107 std::string prefix = "";
00108 pn.getParamCached("tf_prefix",prefix);
00109 ROS_INFO("tf_prefix: %s",prefix.c_str());
00110 if(!mti->setSettings(outputMode, outputSettings, scenario, prefix, frame_id, GPS_lever_arm, 1000))
00111 {
00112 ROS_FATAL("MTi -- Unable to set the output mode and settings.");
00113 ROS_BREAK();
00114 }
00115 ROS_INFO("MTi -- Setup complete! Initiating data streaming...");
00116
00117 ros::Publisher mti_pub = pn.advertise<sensor_msgs::Imu>("imu/data", 10);
00118 ros::Publisher navsat_pub = pn.advertise<sensor_msgs::NavSatFix>("fix", 10);
00119 ros::Publisher odomPub = pn.advertise<nav_msgs::Odometry>("odom",10);
00120
00121 tf::TransformBroadcaster odom_broadcaster;
00122 tf::TransformListener listener;
00123
00124 ros::Rate r(20);
00125 while(ros::ok())
00126 {
00127 ros::Time now = ros::Time::now();
00128 sensor_msgs::Imu imu_msg = mti->fillImuMessage(now);
00129 mti_pub.publish(imu_msg);
00130
00131 sensor_msgs::NavSatFix nav_fix_msg = mti->fillNavFixMessage(now);
00132 navsat_pub.publish(nav_fix_msg);
00133
00134 nav_msgs::Odometry odom_msg = mti->fillOdometryMessage(listener, odom_broadcaster, now);
00135 odomPub.publish(odom_msg);
00136
00137 ros::spinOnce();
00138 r.sleep();
00139 }
00140
00141 return(0);
00142 }
00143
00144
00145