Go to the documentation of this file.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 #include "ekf_interface.h"
00033 #include <tf/tf.h>
00034 #include "helper.h"
00035
00036 EKFInterface::EKFInterface(ros::NodeHandle & nh, CommPtr & comm) :
00037 nh_(nh), pnh_("~"), comm_(comm)
00038 {
00039 state_pub_ = nh.advertise<sensor_fusion_comm::ExtEkf> ("ekf_state_out", 1);
00040 state_sub_ = nh.subscribe("ekf_state_in", 1, &EKFInterface::stateCallback, this);
00041
00042 comm_->registerCallback(HLI_PACKET_ID_EKF_STATE, &EKFInterface::processEkfData, this);
00043 }
00044
00045 void EKFInterface::processEkfData(uint8_t * buf, uint32_t bufLength)
00046 {
00047 static uint32_t seq = 0;
00048 if (state_pub_.getNumSubscribers() > 0)
00049 {
00050 HLI_EKF_STATE * state = (HLI_EKF_STATE*)buf;
00051 sensor_fusion_comm::ExtEkfPtr msg(new sensor_fusion_comm::ExtEkf);
00052
00053 msg->header.stamp = ros::Time(state->timestamp * 1.0e-6);
00054 msg->header.seq = seq;
00055
00056 msg->linear_acceleration.x = helper::asctecAccToSI(state->acc_x);
00057 msg->linear_acceleration.y = helper::asctecAccToSI(state->acc_y);
00058 msg->linear_acceleration.z = helper::asctecAccToSI(state->acc_z);
00059
00060 msg->angular_velocity.x = helper::asctecOmegaToSI(state->ang_vel_roll);
00061 msg->angular_velocity.y = helper::asctecOmegaToSI(state->ang_vel_pitch);
00062 msg->angular_velocity.z = helper::asctecOmegaToSI(state->ang_vel_yaw);
00063
00064 msg->flag = sensor_fusion_comm::ExtEkf::current_state;
00065
00066 msg->state.resize(HLI_EKF_STATE_SIZE);
00067
00068 for (uint32_t i = 0; i < HLI_EKF_STATE_SIZE; i++)
00069 {
00070 msg->state[i] = state->state[i];
00071 }
00072
00073 state_pub_.publish(msg);
00074 }
00075
00076 seq++;
00077 }
00078
00079 void EKFInterface::stateCallback(const sensor_fusion_comm::ExtEkfConstPtr & msg)
00080 {
00081 ekf_state_msg_.timestamp = static_cast<uint64_t> (msg->header.stamp.toSec() * 1.0e6);
00082
00083 switch (msg->flag)
00084 {
00085 case sensor_fusion_comm::ExtEkf::current_state:
00086 ekf_state_msg_.flag = HLI_EKF_STATE_CURRENT_STATE;
00087 break;
00088 case sensor_fusion_comm::ExtEkf::initialization:
00089 ekf_state_msg_.flag = HLI_EKF_STATE_INITIALIZATION;
00090 break;
00091 case sensor_fusion_comm::ExtEkf::state_correction:
00092 ekf_state_msg_.flag = HLI_EKF_STATE_STATE_CORRECTION;
00093 break;
00094 default:
00095 ekf_state_msg_.flag = HLI_EKF_STATE_INITIALIZATION;
00096 }
00097
00098 if (msg->state.size() != HLI_EKF_STATE_SIZE)
00099 {
00100 ROS_WARN_STREAM("size of incoming state ("<< msg->state.size() <<") != size of state in the HL processor ("<< HLI_EKF_STATE_SIZE <<"), not sending!");
00101 return;
00102 }
00103
00104
00105
00106 for (unsigned int i = 0; i < HLI_EKF_STATE_SIZE; i++)
00107 {
00108 ekf_state_msg_.state[i] = msg->state[i];
00109 }
00110
00111 comm_->sendPacket(HLI_PACKET_ID_EKF_STATE, ekf_state_msg_);
00112 }
00113