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 "position_sensor.h"
00033 #include <ssf_core/eigen_utils.h>
00034
00035 #define N_MEAS 9 // measurement size
00036 PositionSensorHandler::PositionSensorHandler(ssf_core::Measurements* meas) :
00037 MeasurementHandler(meas)
00038 {
00039 ros::NodeHandle pnh("~");
00040 pnh.param("measurement_world_sensor", measurement_world_sensor_, true);
00041 pnh.param("use_fixed_covariance", use_fixed_covariance_, false);
00042
00043 ROS_INFO_COND(measurement_world_sensor_, "interpreting measurement as sensor w.r.t. world");
00044 ROS_INFO_COND(!measurement_world_sensor_, "interpreting measurement as world w.r.t. sensor (e.g. ethzasl_ptam)");
00045
00046 ROS_INFO_COND(use_fixed_covariance_, "using fixed covariance");
00047 ROS_INFO_COND(!use_fixed_covariance_, "using covariance from sensor");
00048
00049 subscribe();
00050 }
00051
00052 void PositionSensorHandler::subscribe()
00053 {
00054 ros::NodeHandle nh("ssf_core");
00055 subMeasurement_ = nh.subscribe("position_measurement", 1, &PositionSensorHandler::measurementCallback, this);
00056
00057 measurements->ssf_core_.registerCallback(&PositionSensorHandler::noiseConfig, this);
00058
00059 nh.param("meas_noise1",n_zp_,0.0001);
00060
00061 }
00062
00063 void PositionSensorHandler::noiseConfig(ssf_core::SSF_CoreConfig& config, uint32_t level)
00064 {
00065
00066
00067 this->n_zp_ = config.meas_noise1;
00068
00069
00070 }
00071
00072 void PositionSensorHandler::measurementCallback(const ssf_updates::PositionWithCovarianceStampedConstPtr & msg)
00073 {
00074
00075
00076
00077
00078 ssf_core::State state_old;
00079 ros::Time time_old = msg->header.stamp;
00080 Eigen::Matrix<double,N_MEAS,N_STATE>H_old;
00081 Eigen::Matrix<double, N_MEAS, 1> r_old;
00082 Eigen::Matrix<double,N_MEAS,N_MEAS> R;
00083
00084 H_old.setZero();
00085 R.setZero();
00086
00087
00088 z_p_ = Eigen::Matrix<double,3,1>(msg->position.x, msg->position.y, msg->position.z);
00089
00090
00091 if (!use_fixed_covariance_)
00092 {
00093 R.block(0,0,3,3) = Eigen::Matrix<double,3,3>(&msg->covariance[0]);
00094 Eigen::Matrix<double,6,1> buffvec = Eigen::Matrix<double,6,1>::Constant(1e-6);
00095 R.block(3,3,6,6) = buffvec.asDiagonal();
00096 }
00097 else
00098 {
00099 const double s_zp = n_zp_ * n_zp_;
00100 R = (Eigen::Matrix<double, N_MEAS, 1>() << s_zp, s_zp, s_zp, 1e-6, 1e-6, 1e-6, 1e-6, 1e-6, 1e-6).finished().asDiagonal();
00101 }
00102
00103
00104 measurements->p_vc_ = z_p_;
00105
00106 unsigned char idx = measurements->ssf_core_.getClosestState(&state_old,time_old,0);
00107 if (state_old.time_ == -1)
00108 return;
00109
00110
00111 Eigen::Matrix<double,3,3> C_wv = state_old.q_wv_.conjugate().toRotationMatrix();
00112 Eigen::Matrix<double,3,3> C_q = state_old.q_.conjugate().toRotationMatrix();
00113 Eigen::Matrix<double,3,3> C_ci = state_old.q_ci_.conjugate().toRotationMatrix();
00114
00115
00116 Eigen::Matrix<double,3,1> vecold;
00117 vecold = (state_old.p_+C_q.transpose()*state_old.p_ci_)*state_old.L_;
00118 Eigen::Matrix<double,3,3> skewold = skew(vecold);
00119
00120 Eigen::Matrix<double,3,3> pci_sk = skew(state_old.p_ci_);
00121
00122
00123
00124 H_old.block<3,3>(0,0) = C_wv.transpose()*state_old.L_;
00125 H_old.block<3,3>(0,6) = -C_wv.transpose()*C_q.transpose()*pci_sk*state_old.L_;
00126 H_old.block<3,1>(0,15) = C_wv.transpose()*C_q.transpose()*state_old.p_ci_ + C_wv.transpose()*state_old.p_;
00127 H_old.block<3,3>(0,16) = -C_wv.transpose()*skewold;
00128 H_old.block<3,3>(0,22) = C_wv.transpose()*C_q.transpose()*state_old.L_;
00129 H_old.block<3,3>(3,16) = Eigen::Matrix<double,3,3>::Identity();
00130 H_old.block<3,3>(6,19) = Eigen::Matrix<double,3,3>::Identity();
00131
00132
00133
00134 r_old.block<3,1>(0,0) = z_p_ - C_wv.transpose()*(state_old.p_ + C_q.transpose()*state_old.p_ci_)*state_old.L_;
00135
00136 r_old.block<3,1>(3,0) = -state_old.q_wv_.vec()/state_old.q_wv_.w()*2;
00137
00138 r_old.block<3,1>(6,0) = -state_old.q_ci_.vec()/state_old.q_ci_.w()*2;
00139
00140
00141 measurements->ssf_core_.applyMeasurement(idx,H_old,r_old,R);
00142 }