Skip to content

Commit

Permalink
[ICRA2022] Final config
Browse files Browse the repository at this point in the history
  • Loading branch information
lmark1 committed Sep 10, 2021
1 parent e7f3c40 commit afb2579
Show file tree
Hide file tree
Showing 4 changed files with 8 additions and 4 deletions.
2 changes: 1 addition & 1 deletion src/filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,7 +269,7 @@ void EsEkf2::poseMeasurementUpdateDrift(const Matrix3d& R_cov,
Matrix<double, N_STATES + 2, N_STATES> H_dx = MatrixXd::Zero(N_STATES + 2, N_STATES);
// Scola equation:(280)
H_dx.block<6, 6>(0, 0) = MatrixXd::Identity(6, 6);
H_dx.block<4, 3>(6, 6) = 0.5 * sf::firstOrderApprox(m_est_quaternion);
H_dx.block<4, 3>(6, 6) = 0.5 * sf::firstOrderApproxLocal(m_est_quaternion);
H_dx.block<12, 12>(10, 9) = MatrixXd::Identity(12, 12);
H_dx.block<4, 3>(22, 21) = 0.5 * sf::firstOrderApproxLocal(est_quaternion_drift);

Expand Down
2 changes: 1 addition & 1 deletion src/sensor_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ void SensorClient::stateEstimation(const ros::TimerEvent& /* unused */)
sensor_ptr->publishState(sensor_state);
sensor_ptr->publishTransformedPose();
sensor_ptr->publishDrift();
m_sensor_tf.publishSensorOrigin(*sensor_ptr);
m_sensor_tf.publishSensorOrigin(*sensor_ptr, m_es_ekf.getOrientation());
}

if (!measurement && !prediction) {
Expand Down
6 changes: 5 additions & 1 deletion src/sensor_tf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ sf::SensorTF::SensorTF(std::string base_link) : m_base_link(std::move(base_link)
m_base_link_origin = m_base_link + "/robot";
}

void sf::SensorTF::publishSensorOrigin(const Sensor& sensor)
void sf::SensorTF::publishSensorOrigin(const Sensor& sensor, const Quaterniond& ekf_orientation)
{
Eigen::Vector3d position;
Eigen::Quaterniond orientation;
Expand All @@ -23,6 +23,10 @@ void sf::SensorTF::publishSensorOrigin(const Sensor& sensor)
orientation = sensor.getOrientation();
}

if (!sensor.isOrientationSensor()) {
orientation = ekf_orientation;
}

// Get the inverse transformation
tf2::Transform tf_inv(
tf2::Quaternion(orientation.x(), orientation.y(), orientation.z(), orientation.w()),
Expand Down
2 changes: 1 addition & 1 deletion src/sensor_tf.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ class SensorTF
*
* @param sensor Ovbject type Sensor.
*/
void publishSensorOrigin(const Sensor& sensor);
void publishSensorOrigin(const Sensor& sensor, const Quaterniond& ekf_orientation);

/**
* @brief Publish estimated origin from the odometry message.
Expand Down

0 comments on commit afb2579

Please sign in to comment.