9 nh_(), nh_private_(
"~"), initialized_(
false)
166 ROS_INFO(
"Connecting to serial port \"%s\", at %d baud", port_.c_str(),
baudrate_);
169 ROS_FATAL(
"inertialsense: Unable to open serial port \"%s\", at %d baud", port_.c_str(),
baudrate_);
187 uint32_t
data = nav_dt_ms;
198 set_vector_flash_config<float>(
"INS_rpy_radians", 3, offsetof(
nvm_flash_cfg_t, insRotation));
199 set_vector_flash_config<float>(
"INS_xyz", 3, offsetof(
nvm_flash_cfg_t, insOffset));
200 set_vector_flash_config<float>(
"GPS_ant1_xyz", 3, offsetof(
nvm_flash_cfg_t, gps1AntOffset));
201 set_vector_flash_config<float>(
"GPS_ant2_xyz", 3, offsetof(
nvm_flash_cfg_t, gps2AntOffset));
204 set_flash_config<float>(
"inclination", offsetof(
nvm_flash_cfg_t, magInclination), 0.0f);
205 set_flash_config<float>(
"declination", offsetof(
nvm_flash_cfg_t, magDeclination), 0.0f);
206 set_flash_config<int>(
"dynamic_model", offsetof(
nvm_flash_cfg_t, insDynModel), 8);
207 set_flash_config<int>(
"ser1_baud_rate", offsetof(
nvm_flash_cfg_t, ser1BaudRate), 921600);
212 bool RTK_rover, RTK_rover_radio_enable, RTK_base, dual_GNSS;
213 std::string gps_type;
216 nh_private_.
param<
bool>(
"RTK_rover_radio_enable", RTK_rover_radio_enable,
false);
220 std::string RTK_server_IP, RTK_correction_type;
222 nh_private_.
param<std::string>(
"RTK_server_IP", RTK_server_IP,
"127.0.0.1");
224 nh_private_.
param<std::string>(
"RTK_correction_type", RTK_correction_type,
"UBLOX");
225 ROS_ERROR_COND(RTK_rover && RTK_base,
"unable to configure uINS to be both RTK rover and base - default to rover");
226 ROS_ERROR_COND(RTK_rover && dual_GNSS,
"unable to configure uINS to be both RTK rover as dual GNSS - default to dual GNSS");
228 uint32_t RTKCfgBits = 0;
232 ROS_INFO(
"InertialSense: Configured as dual GNSS (compassing)");
242 if (RTK_rover_radio_enable)
245 ROS_INFO(
"InertialSense: Configured as RTK Rover with radio enabled");
258 std::string RTK_connection = RTK_correction_type +
":" + RTK_server_IP +
":" + std::to_string(RTK_server_port);
259 ROS_INFO(
"InertialSense: Configured as RTK Rover");
264 ROS_INFO_STREAM(
"Successfully connected to " << RTK_connection <<
" RTK server");
276 std::string RTK_connection = RTK_server_IP +
":" + std::to_string(RTK_server_port);
278 ROS_INFO(
"InertialSense: Configured as RTK Base");
284 ROS_INFO_STREAM(
"Successfully created " << RTK_connection <<
" as RTK server");
294 template <
typename T>
296 std::vector<double> tmp(size,0);
300 for (
int i = 0; i < size; i++)
309 template <
typename T>
550 std_msgs::Header strobe_msg;
567 for (
int i = 0; i < 50; i++)
578 sensor_msgs::MagneticField mag_msg;
581 mag_msg.magnetic_field.x = msg->
mag[0];
582 mag_msg.magnetic_field.y = msg->
mag[1];
583 mag_msg.magnetic_field.z = msg->
mag[2];
590 sensor_msgs::FluidPressure baro_msg;
593 baro_msg.fluid_pressure = msg->
bar;
594 baro_msg.variance = msg-> barTemp;
601 inertial_sense::PreIntIMU preintIMU_msg;
603 preintIMU_msg.header.frame_id =
frame_id_;
604 preintIMU_msg.dtheta.x = msg->
theta1[0];
605 preintIMU_msg.dtheta.y = msg->
theta1[1];
606 preintIMU_msg.dtheta.z = msg->
theta1[2];
608 preintIMU_msg.dvel.x = msg->
vel1[0];
609 preintIMU_msg.dvel.y = msg->
vel1[1];
610 preintIMU_msg.dvel.z = msg->
vel1[2];
612 preintIMU_msg.dt = msg->
dt;
621 inertial_sense::RTKInfo rtk_info;
628 rtk_info.BaseLLA[0] = msg->
baseLla[0];
629 rtk_info.BaseLLA[1] = msg->
baseLla[1];
630 rtk_info.BaseLLA[2] = msg->
baseLla[2];
646 inertial_sense::RTKRel rtk_rel;
649 rtk_rel.ar_ratio = msg->
arRatio;
692 for (
int i = 0; i < nObs; i++)
694 inertial_sense::GNSSObservation obs;
696 obs.time.time = msg[i].
time.time;
697 obs.time.sec = msg[i].
time.sec;
698 obs.sat = msg[i].
sat;
700 obs.SNR = msg[i].
SNR[0];
701 obs.LLI = msg[i].
LLI[0];
702 obs.code = msg[i].
code[0];
703 obs.qualL = msg[i].
qualL[0];
704 obs.qualP = msg[i].
qualP[0];
731 inertial_sense::GNSSEphemeris eph;
733 eph.iode = msg->
iode;
734 eph.iodc = msg->
iodc;
737 eph.week = msg->
week;
738 eph.code = msg->
code;
739 eph.flag = msg->
flag;
743 eph.toe.sec = msg->
toe.
sec;
744 eph.toc.sec = msg->
toc.
sec;
745 eph.ttr.sec = msg->
ttr.
sec;
749 eph.OMG0 = msg->
OMG0;
752 eph.deln = msg->
deln;
753 eph.OMGd = msg->
OMGd;
754 eph.idot = msg->
idot;
761 eph.toes = msg->
toes;
766 eph.tgd[0] = msg->
tgd[0];
767 eph.tgd[1] = msg->
tgd[1];
768 eph.tgd[2] = msg->
tgd[2];
769 eph.tgd[3] = msg->
tgd[3];
770 eph.Adot = msg->
Adot;
771 eph.ndot = msg->
ndot;
777 inertial_sense::GlonassEphemeris geph;
779 geph.iode = msg->
iode;
786 geph.toe.sec = msg->
toe.
sec;
787 geph.tof.sec = msg->
tof.
sec;
788 geph.pos[0] = msg->
pos[0];
789 geph.pos[1] = msg->
pos[1];
790 geph.pos[2] = msg->
pos[2];
791 geph.vel[0] = msg->
vel[0];
792 geph.vel[1] = msg->
vel[1];
793 geph.vel[2] = msg->
vel[2];
794 geph.acc[0] = msg->
acc[0];
795 geph.acc[1] = msg->
acc[1];
796 geph.acc[2] = msg->
acc[2];
797 geph.taun = msg->
taun;
798 geph.gamn = msg->
gamn;
799 geph.dtaun = msg->
dtaun;
806 diagnostic_msgs::DiagnosticArray diag_array;
810 diagnostic_msgs::DiagnosticStatus cno_mean;
811 cno_mean.name =
"CNO Mean";
813 cno_mean.message = std::to_string(
gps_msg.cno);
814 diag_array.status.push_back(cno_mean);
817 diagnostic_msgs::DiagnosticStatus rtk_status;
818 rtk_status.name =
"RTK";
820 std::string rtk_message;
823 diagnostic_msgs::KeyValue ar_ratio;
824 ar_ratio.key =
"AR Ratio";
826 rtk_status.values.push_back(ar_ratio);
837 diagnostic_msgs::KeyValue differential_age;
838 differential_age.key =
"Differential Age";
840 rtk_status.values.push_back(differential_age);
843 rtk_message +=
" Differential Age Large";
847 diagnostic_msgs::KeyValue heading_base_to_rover;
848 heading_base_to_rover.key =
"Heading Base to Rover (rad)";
850 rtk_status.values.push_back(heading_base_to_rover);
852 rtk_status.message = rtk_message;
853 diag_array.status.push_back(rtk_status);
862 double current_lla_[3];
863 current_lla_[0] =
lla_[0];
864 current_lla_[1] =
lla_[1];
865 current_lla_[2] =
lla_[2];
884 res.message = (
"Update was succesful. refLla: Lat: " + to_string(current_lla_[0]) +
" Lon: " +to_string( current_lla_[1]) +
" Alt: " + to_string(current_lla_[2]));
890 res.message =
"Unable to update refLLA. Please try again.";
915 res.message = (
"Update was succesful. refLla: Lat: " + to_string(req.lla[0]) +
" Lon: " +to_string( req.lla[1]) +
" Alt: " + to_string(req.lla[2]));
921 res.message =
"Unable to update refLLA. Please try again.";
928 uint32_t single_axis_command = 2;
932 uint8_t buffer[2048];
947 res.message =
"Successfully initiated mag recalibration.";
957 uint32_t multi_axis_command = 1;
961 uint8_t buffer[2048];
976 res.message =
"Successfully initiated mag recalibration.";
996 vector<InertialSense::bootloader_result_t> results =
IS_.
BootloadFile(
"*", req.filename, 921600);
997 if (!results[0].error.empty())
1000 res.message = results[0].error;
1015 uint64_t nsec = (timeOfWeek - floor(timeOfWeek))*1e9;
1081 out.
nsec = subsec * 1e9;
tf::TransformBroadcaster br
float baseToRoverVector[3]
static vector< bootloader_result_t > BootloadFile(const string &comPort, const string &fileName, const string &bootloaderFileName, int baudRate=IS_BAUD_RATE_BOOTLOADER, pfnBootloadProgress uploadProgress=NULLPTR, pfnBootloadProgress verifyProgress=NULLPTR, pfnBootloadStatus infoProgress=NULLPTR, bool updateBootloader=false)
bool update_firmware_srv_callback(inertial_sense::FirmwareUpdate::Request &req, inertial_sense::FirmwareUpdate::Response &res)
uint32_t baseGpsEphemerisCount
int serialPortReadCharTimeout(serial_port_t *serialPort, unsigned char *c, int timeoutMilliseconds)
ros::Publisher strobe_pub_
ros::NodeHandle nh_private_
ros::Time ros_time_from_gtime(const uint64_t sec, double subsec)
inertial_sense::INL2States inl2_states_msg
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void RTK_Rel_callback(const gps_rtk_rel_t *const msg)
void mag_callback(const magnetometer_t *const msg)
void GPS_raw_callback(const gps_raw_t *const msg)
#define DID_GPS2_RTK_CMP_REL
void preint_IMU_callback(const preintegrated_imu_t *const msg)
obsd_t obs[MAX_OBSERVATION_COUNT_IN_RTK_MESSAGE]
const dev_info_t GetDeviceInfo(int pHandle=0)
bool OpenServerConnection(const string &connectionString)
geometry_msgs::Vector3Stamped gps_velEcef
uint32_t baseGpsObservationCount
void GPS_info_callback(const gps_sat_t *const msg)
float diagnostic_heading_base_to_rover_
float diagnostic_differential_age_
protocol_type_t is_comm_parse_byte(is_comm_instance_t *instance, uint8_t byte)
void GPS_pos_callback(const gps_pos_t *const msg)
void INS1_callback(const ins_1_t *const msg)
void RTK_Misc_callback(const gps_rtk_misc_t *const msg)
ros::Timer obs_bundle_timer_
#define DID_PREINTEGRATED_IMU
inertial_sense::GPS gps_msg
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void diagnostics_callback(const ros::TimerEvent &event)
#define ROS_ERROR_COND(cond,...)
void comManagerStep(void)
bool CreateHost(const string &ipAndPort)
float baseToRoverDistance
uint32_t roverGlonassObservationCount
nav_msgs::Odometry odom_msg
void SendData(eDataIDs dataId, uint8_t *data, uint32_t length, uint32_t offset)
uint32_t roverGpsObservationCount
ros::ServiceServer firmware_update_srv_
bool SetLoggerEnabled(bool enable, const string &path=cISLogger::g_emptyString, cISLogger::eLogType logType=cISLogger::eLogType::LOGTYPE_DAT, uint64_t rmcPreset=RMC_PRESET_PPD_BITS, float maxDiskSpacePercent=0.5f, uint32_t maxFileSize=1024 *1024 *5, const string &subFolder=cISLogger::g_emptyString)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
uint32_t roverBeidouEphemerisCount
void publish(const boost::shared_ptr< M > &message) const
#define RMC_PRESET_PPD_ROBOT
double tow_from_ros_time(const ros::Time &rt)
void GPS_vel_callback(const gps_vel_t *const msg)
nvm_flash_cfg_t GetFlashConfig(int pHandle=0)
void strobe_in_time_callback(const strobe_in_time_t *const msg)
void INS2_callback(const ins_2_t *const msg)
ros::ServiceServer mag_cal_srv_
float diagnostic_ar_ratio_
uint32_t baseAntennaCount
sensor_msgs::Imu imu2_msg
static void quaternionMsgToTF(const geometry_msgs::Quaternion &msg, Quaternion &bt)
ros::Timer diagnostics_timer_
bool getParam(const std::string &key, std::string &s) const
ros::Time ros_time_from_start_time(const double time)
ros_time_from_start_time
void set_flash_config(std::string param_name, uint32_t offset, T def) __attribute__((optimize(0)))
#define DID_GPS2_RTK_CMP_MISC
void configure_ascii_output()
uint32_t roverGpsEphemerisCount
void set_vector_flash_config(std::string param_name, uint32_t size, uint32_t offset)
#define UNIX_TO_GPS_OFFSET
void GPS_obs_callback(const obsd_t *const msg, int nObs)
uint32_t roverGlonassEphemerisCount
#define SET_CALLBACK(DID, __type, __cb_fun, __periodmultiple)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define DID_MAGNETOMETER_1
ros::ServiceServer multi_mag_cal_srv_
USBInterfaceDescriptor data
bool hasParam(const std::string &key) const
uint32_t baseGalileoEphemerisCount
ros::Time ros_time_from_tow(const double tow)
ros_time_from_tow Get equivalent ros time from tow and internal week counter
void GPS_geph_callback(const geph_t *const msg)
void is_comm_init(is_comm_instance_t *instance, uint8_t *buffer, int bufferSize)
uint32_t roverGalileoEphemerisCount
ros_stream_t INL2_states_
inertial_sense::GPSInfo gps_info_msg
uint32_t baseGalileoObservationCount
ros::ServiceServer refLLA_set_current_srv_
uint32_t baseGlonassEphemerisCount
std::string getTopic() const
bool Open(const char *port, int baudRate=IS_COM_BAUDRATE_DEFAULT, bool disableBroadcastsOnClose=false)
void configure_parameters()
#define ROS_INFO_STREAM(args)
bool perform_mag_cal_srv_callback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
sensor_msgs::Imu imu1_msg
void GPS_eph_callback(const eph_t *const msg)
serial_port_t * GetSerialPort(int pHandle=0)
void configure_data_streams()
ros::Time ros_time_from_week_and_tow(const uint32_t week, const double timeOfWeek)
ros_time_from_week_and_tow Get current ROS time from week and tow
void GPS_obs_bundle_timer_callback(const ros::TimerEvent &e)
gps_sat_sv_t sat[MAX_NUM_SAT_CHANNELS]
bool set_current_position_as_refLLA(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros::ServiceServer refLLA_set_value_srv_
#define DID_STROBE_IN_TIME
uint32_t roverGalileoObservationCount
#define DID_GPS1_RTK_POS_REL
static string CreateCurrentTimestamp()
uint32_t baseBeidouObservationCount
uint32_t roverBeidouObservationCount
void set_navigation_dt_ms()
void comManagerGetData(int pHandle, uint32_t dataId, int offset, int size, int periodMultiple)
Request data This function requests the specified data w/ offset and length for partial reads...
void IMU_callback(const dual_imu_t *const msg)
void baro_callback(const barometer_t *const msg)
#define ROS_ERROR_STREAM(args)
uint32_t baseBeidouEphemerisCount
bool set_refLLA_to_value(inertial_sense::refLLAUpdate::Request &req, inertial_sense::refLLAUpdate::Response &res)
inertial_sense::GNSSObsVec obs_Vec_
bool perform_multi_mag_cal_srv_callback(std_srvs::Trigger::Request &req, std_srvs::Trigger::Response &res)
ros_stream_t diagnostics_
uint32_t baseGlonassObservationCount
#define DID_GPS1_RTK_POS_MISC
void INL2_states_callback(const inl2_states_t *const msg)