Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Estimation][VO] Refactor throttle/decimate process #558

Merged
merged 1 commit into from
Sep 12, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -75,6 +75,7 @@ namespace sensor_plugin
ros::Timer servo_control_timer_;

/* ros param */
double throttle_rate_;
double level_pos_noise_sigma_;
double z_pos_noise_sigma_;
double vel_noise_sigma_;
Expand Down
18 changes: 12 additions & 6 deletions aerial_robot_estimation/src/sensor/vo.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,6 @@ namespace
tf::Transform prev_sensor_tf;
tf::Vector3 baselink_omega;
tf::Matrix3x3 baselink_r;

//debug
double sample_interval = 0.02; //50 hz
}

namespace sensor_plugin
Expand Down Expand Up @@ -99,8 +96,6 @@ namespace sensor_plugin

void VisualOdometry::voCallback(const nav_msgs::Odometry::ConstPtr & vo_msg)
{
//if(vo_msg->header.stamp.toSec() - prev_timestamp_ < sample_interval) return;

/* only do egmotion estimate mode */
if(!getFuserActivate(aerial_robot_estimation::EGOMOTION_ESTIMATE))
{
Expand Down Expand Up @@ -139,9 +134,19 @@ namespace sensor_plugin
tf::Transform raw_sensor_tf;
tf::poseMsgToTF(vo_msg->pose.pose, raw_sensor_tf); // motion update

curr_timestamp_ = vo_msg->header.stamp.toSec() + delay_; //temporal update
/* temporal update */
curr_timestamp_ = vo_msg->header.stamp.toSec() + delay_;
reference_timestamp_ = curr_timestamp_;

/* throttle message */
if(throttle_rate_ > 0)
{
if (curr_timestamp_ - prev_timestamp_ < 1 / throttle_rate_)
{
return;
}
}

if(getStatus() == Status::INACTIVE)
{
/* for z */
Expand Down Expand Up @@ -598,6 +603,7 @@ namespace sensor_plugin
getParam<bool>("z_vel_mode", z_vel_mode_, false);
getParam<bool>("z_no_delay", z_no_delay_, false);
getParam<bool>("outdoor_no_vel_time_sync", outdoor_no_vel_time_sync_, false);
getParam<double>("throttle_rate", throttle_rate_, 0.0);
getParam<double>("level_pos_noise_sigma", level_pos_noise_sigma_, 0.01 );
getParam<double>("z_pos_noise_sigma", z_pos_noise_sigma_, 0.01 );
getParam<double>("vel_noise_sigma", vel_noise_sigma_, 0.05 );
Expand Down
Loading