-
Notifications
You must be signed in to change notification settings - Fork 2
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
reorganize estimator inheritence structure
- Loading branch information
1 parent
9f8122b
commit 16adbeb
Showing
12 changed files
with
151 additions
and
232 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file was deleted.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file was deleted.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,91 @@ | ||
// MIT License | ||
// | ||
// Copyright (c) 2023 Stanford Autonomous Systems Lab | ||
// | ||
// Permission is hereby granted, free of charge, to any person obtaining a copy | ||
// of this software and associated documentation files (the "Software"), to deal | ||
// in the Software without restriction, including without limitation the rights | ||
// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell | ||
// copies of the Software, and to permit persons to whom the Software is | ||
// furnished to do so, subject to the following conditions: | ||
// | ||
// The above copyright notice and this permission notice shall be included in all | ||
// copies or substantial portions of the Software. | ||
// | ||
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR | ||
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, | ||
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE | ||
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER | ||
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, | ||
// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE | ||
// SOFTWARE. | ||
|
||
|
||
#include "ff_estimate/base_mocap_estimator.hpp" | ||
|
||
using ff_msgs::msg::FreeFlyerState; | ||
using ff_msgs::msg::Pose2DStamped; | ||
|
||
class MovingAvgEstimatorNode : public ff::BaseMocapEstimator | ||
{ | ||
public: | ||
MovingAvgEstimatorNode() | ||
: ff::BaseMocapEstimator("moving_avg_estimator") | ||
{ | ||
// perform simple 1st order IIR lowpass filter on derivate estimates | ||
// coefficient in [0, 1) (higher coefficient filters better with larger delay) | ||
this->declare_parameter("lowpass_coeff", .95); | ||
this->declare_parameter("min_dt", 0.005); | ||
} | ||
|
||
void EstimateWithPose2D(const Pose2DStamped & pose_stamped) override | ||
{ | ||
FreeFlyerState state{}; | ||
|
||
state.pose = pose_stamped.pose; | ||
if (prev_state_ready_) { | ||
const rclcpp::Time now = pose_stamped.header.stamp; | ||
const rclcpp::Time last = prev_.header.stamp; | ||
double dt = (now - last).seconds(); | ||
|
||
// ignore this frame if it is too close to the last frame | ||
if (dt < this->get_parameter("min_dt").as_double()) { | ||
return; | ||
} | ||
|
||
// finite difference | ||
double vx = (pose_stamped.pose.x - prev_.state.pose.x) / dt; | ||
double vy = (pose_stamped.pose.y - prev_.state.pose.y) / dt; | ||
// wrap angle delta to [-pi, pi] | ||
double dtheta = std::remainder(pose_stamped.pose.theta - prev_.state.pose.theta, 2 * M_PI); | ||
double wz = dtheta / dt; | ||
|
||
double alpha = this->get_parameter("lowpass_coeff").as_double(); | ||
if (alpha < 0 || alpha >= 1) { | ||
RCLCPP_ERROR(this->get_logger(), "IIR filter disabled: invalid coefficient %f", alpha); | ||
alpha = 0; | ||
} | ||
state.twist.vx = alpha * prev_.state.twist.vx + (1. - alpha) * vx; | ||
state.twist.vy = alpha * prev_.state.twist.vy + (1. - alpha) * vy; | ||
state.twist.wz = alpha * prev_.state.twist.wz + (1. - alpha) * wz; | ||
} else { | ||
prev_state_ready_ = true; | ||
} | ||
|
||
prev_.state = state; | ||
prev_.header = pose_stamped.header; | ||
|
||
SendStateEstimate(state); | ||
} | ||
|
||
private: | ||
ff_msgs::msg::FreeFlyerStateStamped prev_; | ||
bool prev_state_ready_ = false; | ||
}; | ||
|
||
int main(int argc, char ** argv) | ||
{ | ||
rclcpp::init(argc, argv); | ||
rclcpp::spin(std::make_shared<MovingAvgEstimatorNode>()); | ||
rclcpp::shutdown(); | ||
} |
Oops, something went wrong.