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

fix: some fix on calibration_adapter and parameter_estimator #127

Merged
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 @@ -46,6 +46,7 @@ class CalibrationAdapterNode : public CalibrationAdapterNodeBase
rclcpp::Publisher<Float32Stamped>::SharedPtr pub_acceleration_status_;
rclcpp::Publisher<Float32Stamped>::SharedPtr pub_acceleration_cmd_;
rclcpp::Publisher<Float32Stamped>::SharedPtr pub_steering_angle_cmd_;
rclcpp::Publisher<TwistStamped>::SharedPtr pub_vehicle_twist_;
rclcpp::Subscription<ControlCommandStamped>::SharedPtr sub_control_cmd_;
rclcpp::Subscription<Velocity>::SharedPtr sub_twist_;
template <class T>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -30,5 +30,6 @@
<remap from="~/output/acceleration_status" to="/calibration/vehicle/acceleration_status"/>
<remap from="~/output/steering_angle_cmd" to="/calibration/vehicle/steering_angle_cmd"/>
<remap from="~/output/steering_angle_status" to="/calibration/vehicle/steering_angle_status"/>
<remap from="~/output/vehicle_twist" to="/calibration/vehicle/twist_status"/>
</node>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ CalibrationAdapterNode::CalibrationAdapterNode()
create_publisher<Float32Stamped>("~/output/acceleration_status", durable_qos);
pub_acceleration_cmd_ =
create_publisher<Float32Stamped>("~/output/acceleration_cmd", durable_qos);
pub_vehicle_twist_ = create_publisher<TwistStamped>("~/output/vehicle_twist", durable_qos);

sub_control_cmd_ = create_subscription<ControlCommandStamped>(
"~/input/control_cmd", queue_size,
Expand Down Expand Up @@ -106,6 +107,9 @@ void CalibrationAdapterNode::callbackTwistStatus(const Velocity::ConstSharedPtr
TwistStamped twist;
twist.header = msg->header;
twist.twist.linear.x = msg->longitudinal_velocity;
twist.twist.linear.y = msg->lateral_velocity;
twist.twist.angular.z = msg->heading_rate;
pub_vehicle_twist_->publish(twist);
if (!twist_vec_.empty()) {
const auto past_msg = getNearestTimeDataFromVec(twist, dif_twist_time_, twist_vec_);
const double dt =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,7 @@ class ParameterEstimatorNode : public rclcpp::Node
bool select_gear_ratio_estimator;
bool select_steer_offset_estimator;
bool select_wheel_base_estimator;
bool invert_imu_z;

double auto_mode_duration_ = 0;
double last_manual_time_ = 0;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
<arg name="select_gear_ratio_estimator" default="true" description="Select gear ratio estimator"/>
<arg name="select_steer_offset_estimator" default="true" description="Select steer offset estimator"/>
<arg name="select_wheel_base_estimator" default="true" description="Select wheel base estimator"/>
<arg name="invert_imu_z" default="true" description="Invert z-angular velocity from imu"/>

<!-- get wheel base from vehicle info -->
<include file="$(find-pkg-share global_parameter_loader)/launch/global_params.launch.py">
Expand All @@ -26,8 +27,9 @@
<param name="select_steer_offset_estimator" value="$(var select_steer_offset_estimator)"/>
<param name="select_wheel_base_estimator" value="$(var select_wheel_base_estimator)"/>
<param name="use_auto_mode" value="$(var use_auto_mode)"/>
<param name="invert_imu_z" value="$(var invert_imu_z)"/>
<remap from="input/imu_twist" to="$(var imu_twist)"/>
<remap from="input/vehicle_twist" to="/vehicle/status/twist"/>
<remap from="input/vehicle_twist" to="/calibration/vehicle/twist_status"/>
<remap from="input/control_mode" to="/vehicle/status/control_mode"/>
<remap from="input/handle_status" to="/calibration/vehicle/handle_status"/>
<remap from="input/steer" to="/calibration/vehicle/steering_angle_status"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ ParameterEstimatorNode::ParameterEstimatorNode(const rclcpp::NodeOptions & node_
select_steer_offset_estimator =
this->declare_parameter<bool>("select_steer_offset_estimator", true);
select_wheel_base_estimator = this->declare_parameter<bool>("select_wheel_base_estimator", true);
invert_imu_z = this->declare_parameter<bool>("invert_imu_z", true);
params_.valid_max_steer_rad = this->declare_parameter<double>("valid_max_steer_rad", 0.05);
params_.valid_min_velocity = this->declare_parameter<double>("valid_min_velocity", 0.5);
params_.valid_min_angular_velocity =
Expand Down Expand Up @@ -122,7 +123,7 @@ void ParameterEstimatorNode::timerCallback()
{
VehicleData v = {};
v.velocity = vehicle_twist_ptr_->twist.linear.x;
v.angular_velocity = -imu_ptr_->angular_velocity.z;
v.angular_velocity = imu_ptr_->angular_velocity.z * (invert_imu_z ? -1 : 1);
if (select_steer_offset_estimator || select_wheel_base_estimator) {
v.steer = steer_ptr_->data;
}
Expand Down
Loading