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

Add gimbal cascade pid and modify bullet_solver #162

Merged
merged 53 commits into from
May 8, 2024
Merged
Show file tree
Hide file tree
Changes from 42 commits
Commits
Show all changes
53 commits
Select commit Hold shift + click to select a range
9927d0d
Add chassis vel feedforward for yaw.
1moule Apr 2, 2024
adc60be
Use lp filter to estimate chassis angular velocity.
liyixin135 Apr 3, 2024
1880ed7
Finish the target position and compensation of yaw.
liyixin135 Apr 3, 2024
8700331
Add flag by subscribing vision target changed.
liyixin135 Apr 4, 2024
00ecfab
Control fire near switching target.
liyixin135 Apr 4, 2024
d5ee264
Modify switch limit.
liyixin135 Apr 4, 2024
105f1b9
Modify switch angle.
liyixin135 Apr 4, 2024
d41e046
Modify something wrong.
liyixin135 Apr 4, 2024
53f4a43
Add mode for suggest fire.
liyixin135 Apr 4, 2024
907918f
Add suggest_fire near switching armor.
liyixin135 Apr 4, 2024
b1e8201
Add dynamic reconfig.
liyixin135 Apr 4, 2024
c675052
Add angles' dynamic reconfig.
liyixin135 Apr 4, 2024
da4a085
Modify something wrong.
liyixin135 Apr 4, 2024
14f4467
Add dynamic reconfig.
liyixin135 Apr 4, 2024
99b4063
Modify something wrong.
liyixin135 Apr 4, 2024
47b6162
Modify something wrong.
liyixin135 Apr 4, 2024
e48f42e
Add delay.
liyixin135 Apr 4, 2024
de6d6d7
Delete switching armor target when in low v_yaw.
liyixin135 Apr 4, 2024
5beff48
Delete delay for moving.
liyixin135 Apr 4, 2024
d7c2306
Delete pitch feedforward.
liyixin135 Apr 6, 2024
b22a806
Merge pull request #3 from liyixin135/my_test_dev
1moule Apr 11, 2024
f7a8fe5
Delete friction feedforward.
1moule Apr 12, 2024
4088582
Modify namespace.
1moule Apr 12, 2024
889ffec
Modify some variable and function names.
1moule Apr 12, 2024
ccbf157
Modify variable name.
1moule Apr 12, 2024
5eb12e1
Modify expression of shoot beforehand cmd.
1moule Apr 12, 2024
96cb624
Modify variable name.
1moule Apr 12, 2024
393241c
Publish fly time.
1moule Apr 12, 2024
440aa04
Modify description of variable in cfg.
1moule Apr 12, 2024
34e03f5
Only use target vel for feedforward and enable gravity feedforward on…
1moule Apr 12, 2024
c20dfec
Thinking the situation of tracking center.
liyixin135 Apr 16, 2024
27ed0d9
Add delay2 used to estimate current armor's position when moving.
liyixin135 Apr 16, 2024
5f77ef5
Merge branch 'master' into final-gimbal
liyixin135 Apr 23, 2024
6c6c251
Make sure switch angle when facing different v_yaw's target.
liyixin135 Apr 23, 2024
efb566f
Add GimbalBase.cfg in cmakelist.
liyixin135 Apr 23, 2024
56e9831
Add ramp filter for rate_yaw and rate_pitch.
liyixin135 Apr 27, 2024
a4cdb99
Add count to judge whether switch target.
liyixin135 Apr 27, 2024
b2acbf1
Modify param name.
liyixin135 Apr 27, 2024
45ddcc4
Modify param name.
liyixin135 Apr 27, 2024
53b86d3
Delete lp filter which used to estimate chassis angular vel.
liyixin135 Apr 28, 2024
f2c7935
Add param to dynamic reconfigure.
liyixin135 Apr 28, 2024
700e6ec
Use base_link2pitch to calculate gravity compensation.
liyixin135 Apr 28, 2024
94488c8
Modify topic's name.
liyixin135 Apr 29, 2024
03f03a0
Delete something unused.
liyixin135 May 3, 2024
2e259a3
Used for vision's topic which is called change.
liyixin135 May 5, 2024
caa9190
Delete something unused.
liyixin135 May 5, 2024
ae0ff13
Update cfg.
liyixin135 May 6, 2024
e0503cf
Delete something unused and modify param name.
liyixin135 May 6, 2024
28bbefa
Add some param and modify param name.
liyixin135 May 6, 2024
05eb17a
Modify param name,delete something unused and add chassis vel into so…
liyixin135 May 6, 2024
e9dad34
Modify param name,add delay when rotation and moving,and think about …
liyixin135 May 6, 2024
2fa2b16
Modify cfg's description.
liyixin135 May 8, 2024
7364ccc
Add cfg and modify param name.
liyixin135 May 8, 2024
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
1 change: 1 addition & 0 deletions rm_gimbal_controllers/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@ find_package(catkin REQUIRED

generate_dynamic_reconfigure_options(
cfg/BulletSolver.cfg
cfg/GimbalBase.cfg
)

###################################
Expand Down
5 changes: 5 additions & 0 deletions rm_gimbal_controllers/cfg/BulletSolver.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -14,5 +14,10 @@ gen.add("g", double_t, 0, "Air resistance divided by mass", 9.8, 9.6, 10.0)
gen.add("delay", double_t, 0, "Delay of bullet firing", 0.0, 0, 0.5)
gen.add("dt", double_t, 0, "Iteration interval", 0.01, 0.0001, 0.1)
gen.add("timeout", double_t, 0, "Flight time exceeded", 2.0, 0.5, 3.0)
gen.add("ban_shoot_duration", double_t, 0, "Ban shoot duration while beforehand shooting", 0.0, 0.0, 2.0)
gen.add("gimbal_switch_duration", double_t, 0, "Gimbal switch duration", 0.0, 0.0, 2.0)
gen.add("max_switch_angle_", double_t, 0, "Max switch angle", 40.0, 0.0, 90.0)
gen.add("min_switch_angle_", double_t, 0, "Min switch angle", 2.0, 0.0, 90.0)
gen.add("min_fit_switch_count_", int_t, 0, "Min count that current angle fit switch angle", 0, 3, 99)

exit(gen.generate(PACKAGE, "bullet_solver", "BulletSolver"))
16 changes: 16 additions & 0 deletions rm_gimbal_controllers/cfg/GimbalBase.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
#!/usr/bin/env python
PACKAGE = "rm_gimbal_controllers"

from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

gen.add("yaw_k_v_", double_t, 0, "Yaw input feedforward scale", 0.0, 0, 1.0)
gen.add("pitch_k_v_", double_t, 0, "Pitch input feedforward scale", 0.0, 0, 1.0)
gen.add("accel_yaw_", double_t, 0, "Pitch input feedforward scale", 0.0, 0, 999.0)
gen.add("accel_pitch_", double_t, 0, "Pitch input feedforward scale", 0.0, 0, 999.0)
gen.add("k_chassis_vel_", double_t, 0, "Yaw chassis velocity feedforward scale", 0.0, 0, 1.0)
gen.add("track_rotate_target_delay", double_t, 0, "Used to estimate current armor's yaw", 0.0, -1.0, 1.0)
gen.add("track_move_target_delay", double_t, 0, "Used to estimate current armor's position when moving", 0.0, -1.0, 1.0)

exit(gen.generate(PACKAGE, "gimbal_base", "GimbalBase"))
Original file line number Diff line number Diff line change
Expand Up @@ -46,13 +46,19 @@
#include <rm_common/hardware_interface/robot_state_interface.h>
#include <rm_common/eigen_types.h>
#include <rm_common/ros_utilities.h>
#include <std_msgs/Bool.h>
liyixin135 marked this conversation as resolved.
Show resolved Hide resolved
#include <std_msgs/Float64.h>
#include <rm_msgs/TrackData.h>
#include <rm_msgs/ShootBeforehandCmd.h>

namespace rm_gimbal_controllers
{
struct Config
{
double resistance_coff_qd_10, resistance_coff_qd_15, resistance_coff_qd_16, resistance_coff_qd_18,
resistance_coff_qd_30, g, delay, dt, timeout;
resistance_coff_qd_30, g, delay, dt, timeout, ban_shoot_duration, gimbal_switch_duration, max_switch_angle_,
min_switch_angle_;
int min_fit_switch_count_;
};

class BulletSolver
Expand All @@ -76,22 +82,32 @@ class BulletSolver
void getSelectedArmorPosAndVel(geometry_msgs::Point& armor_pos, geometry_msgs::Vector3& armor_vel,
geometry_msgs::Point pos, geometry_msgs::Vector3 vel, double yaw, double v_yaw,
double r1, double r2, double dz, int armors_num);
void judgeShootBeforehand(const ros::Time& time);
void bulletModelPub(const geometry_msgs::TransformStamped& odom2pitch, const ros::Time& time);
void identifiedTargetChangeCB(const std_msgs::BoolConstPtr& msg);
void reconfigCB(rm_gimbal_controllers::BulletSolverConfig& config, uint32_t);
~BulletSolver() = default;

private:
std::shared_ptr<realtime_tools::RealtimePublisher<visualization_msgs::Marker>> path_desire_pub_;
std::shared_ptr<realtime_tools::RealtimePublisher<visualization_msgs::Marker>> path_real_pub_;
std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::ShootBeforehandCmd>> shoot_beforehand_cmd_pub_;
std::shared_ptr<realtime_tools::RealtimePublisher<std_msgs::Float64>> fly_time_pub_;
ros::Subscriber identified_target_change_sub_;
ros::Time switch_armor_time_{};
realtime_tools::RealtimeBuffer<Config> config_rt_buffer_;
dynamic_reconfigure::Server<rm_gimbal_controllers::BulletSolverConfig>* d_srv_{};
Config config_{};
double max_track_target_vel_;
bool dynamic_reconfig_initialized_{};
double output_yaw_{}, output_pitch_{};
double bullet_speed_{}, resistance_coff_{};
int shoot_beforehand_cmd_{};
int selected_armor_;
int count_;
bool track_target_;
bool identified_target_change_ = true;
bool is_in_delay_before_switch_{};
bool dynamic_reconfig_initialized_{};

geometry_msgs::Point target_pos_{};
double fly_time_;
Expand Down
47 changes: 32 additions & 15 deletions rm_gimbal_controllers/include/rm_gimbal_controllers/gimbal_base.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,22 +38,34 @@
#pragma once

#include <effort_controllers/joint_position_controller.h>
liyixin135 marked this conversation as resolved.
Show resolved Hide resolved
#include <effort_controllers/joint_velocity_controller.h>
#include <controller_interface/multi_interface_controller.h>
#include <hardware_interface/joint_command_interface.h>
#include <rm_common/hardware_interface/robot_state_interface.h>
#include <hardware_interface/imu_sensor_interface.h>
#include <realtime_tools/realtime_publisher.h>
#include <rm_common/hardware_interface/robot_state_interface.h>
#include <rm_common/filters/filters.h>
#include <rm_msgs/GimbalCmd.h>
#include <rm_msgs/TrackData.h>
#include <rm_msgs/GimbalDesError.h>
#include <dynamic_reconfigure/server.h>
#include <rm_msgs/GimbalPosState.h>
#include <rm_gimbal_controllers/GimbalBaseConfig.h>
#include <rm_gimbal_controllers/bullet_solver.h>
#include <tf2_eigen/tf2_eigen.h>
#include <Eigen/Eigen>
#include <rm_common/filters/filters.h>
#include <control_toolbox/pid.h>
#include <urdf/model.h>
#include <dynamic_reconfigure/server.h>
#include <realtime_tools/realtime_publisher.h>

namespace rm_gimbal_controllers
{
struct GimbalConfig
{
double yaw_k_v_, pitch_k_v_, k_chassis_vel_;
double accel_pitch_{}, accel_yaw_{};
double track_rotate_target_delay, track_move_target_delay;
};

class ChassisVel
{
public:
Expand Down Expand Up @@ -139,48 +151,53 @@ class Controller : public controller_interface::MultiInterfaceController<rm_cont
void updateChassisVel();
void commandCB(const rm_msgs::GimbalCmdConstPtr& msg);
void trackCB(const rm_msgs::TrackDataConstPtr& msg);
void reconfigCB(rm_gimbal_controllers::GimbalBaseConfig& config, uint32_t);

rm_control::RobotStateHandle robot_state_handle_;
hardware_interface::ImuSensorHandle imu_sensor_handle_;
bool has_imu_ = true;
effort_controllers::JointPositionController ctrl_yaw_, ctrl_pitch_;
effort_controllers::JointVelocityController ctrl_yaw_, ctrl_pitch_;
control_toolbox::Pid pid_yaw_pos_, pid_pitch_pos_;

std::shared_ptr<BulletSolver> bullet_solver_;

// ROS Interface
ros::Time last_publish_time_{};
std::unique_ptr<realtime_tools::RealtimePublisher<rm_msgs::GimbalPosState>> pid_yaw_pos_state_pub_,
pid_pitch_pos_state_pub_;
std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::GimbalDesError>> error_pub_;
ros::Subscriber cmd_gimbal_sub_;
ros::Subscriber data_track_sub_;
realtime_tools::RealtimeBuffer<rm_msgs::GimbalCmd> cmd_rt_buffer_;
realtime_tools::RealtimeBuffer<rm_msgs::TrackData> track_rt_buffer_;
urdf::JointConstSharedPtr pitch_joint_urdf_, yaw_joint_urdf_;

rm_msgs::GimbalCmd cmd_gimbal_;
rm_msgs::TrackData data_track_;
std::string gimbal_des_frame_id_{}, imu_name_{};
double publish_rate_{};
bool state_changed_{};
bool pitch_des_in_limit{}, yaw_des_in_limit_{};
int loop_count_{};

// Transform
geometry_msgs::TransformStamped odom2gimbal_des_, odom2pitch_, odom2base_, last_odom2base_;
geometry_msgs::TransformStamped odom2gimbal_des_, odom2pitch_, odom2base_, last_odom2base_, last_odom2gimbal_des_;

// Gravity Compensation
geometry_msgs::Vector3 mass_origin_;
double gravity_;
bool enable_gravity_compensation_;

// Input feedforward
double yaw_k_v_;
double pitch_k_v_;

// Resistance compensation
double yaw_resistance_;
double velocity_saturation_point_, effort_saturation_point_;

// Chassis
double k_chassis_vel_;
std::shared_ptr<ChassisVel> chassis_vel_;

bool dynamic_reconfig_initialized_{};
GimbalConfig config_{};
realtime_tools::RealtimeBuffer<GimbalConfig> config_rt_buffer_;
dynamic_reconfigure::Server<rm_gimbal_controllers::GimbalBaseConfig>* d_srv_{};

RampFilter<double>*ramp_rate_pitch_{}, *ramp_rate_yaw_{};

enum
{
RATE,
Expand Down
93 changes: 82 additions & 11 deletions rm_gimbal_controllers/src/bullet_solver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,12 @@ BulletSolver::BulletSolver(ros::NodeHandle& controller_nh)
.g = getParam(controller_nh, "g", 0.),
.delay = getParam(controller_nh, "delay", 0.),
.dt = getParam(controller_nh, "dt", 0.),
.timeout = getParam(controller_nh, "timeout", 0.) };
.timeout = getParam(controller_nh, "timeout", 0.),
.ban_shoot_duration = getParam(controller_nh, "ban_shoot_duration", 0.0),
.gimbal_switch_duration = getParam(controller_nh, "gimbal_switch_duration", 0.0),
.max_switch_angle_ = getParam(controller_nh, "max_switch_angle", 40.0),
.min_switch_angle_ = getParam(controller_nh, "min_switch_angle", 2.0),
.min_fit_switch_count_ = getParam(controller_nh, "min_fit_switch_count", 3) };
max_track_target_vel_ = getParam(controller_nh, "max_track_target_vel", 5.0);
config_rt_buffer_.initRT(config_);

Expand Down Expand Up @@ -80,6 +85,12 @@ BulletSolver::BulletSolver(ros::NodeHandle& controller_nh)
new realtime_tools::RealtimePublisher<visualization_msgs::Marker>(controller_nh, "model_desire", 10));
path_real_pub_.reset(
new realtime_tools::RealtimePublisher<visualization_msgs::Marker>(controller_nh, "model_real", 10));
shoot_beforehand_cmd_pub_.reset(
new realtime_tools::RealtimePublisher<rm_msgs::ShootBeforehandCmd>(controller_nh, "shoot_beforehand_cmd", 10));
fly_time_pub_.reset(new realtime_tools::RealtimePublisher<std_msgs::Float64>(controller_nh, "fly_time", 10));

identified_target_change_sub_ = controller_nh.subscribe<std_msgs::Bool>(
"/armor_processor/change", 10, &BulletSolver::identifiedTargetChangeCB, this);
}

double BulletSolver::getResistanceCoefficient(double bullet_speed) const
Expand Down Expand Up @@ -115,17 +126,36 @@ bool BulletSolver::solve(geometry_msgs::Point pos, geometry_msgs::Vector3 vel, d
selected_armor_ = 0;
double r = r1;
double z = pos.z;
double max_switch_angle_ = config_.max_switch_angle_ / 180 * M_PI;
double min_switch_angle_ = config_.min_switch_angle_ / 180 * M_PI;
track_target_ = std::abs(v_yaw) < max_track_target_vel_;
double switch_armor_angle = track_target_ ?
acos(r / target_rho) - M_PI / 12 +
(-acos(r / target_rho) + M_PI / 6) * std::abs(v_yaw) / max_track_target_vel_ :
M_PI / 12;
if ((((yaw + v_yaw * rough_fly_time) > output_yaw_ + switch_armor_angle) && v_yaw > 0.) ||
(((yaw + v_yaw * rough_fly_time) < output_yaw_ - switch_armor_angle) && v_yaw < 0.))
double switch_armor_angle = track_target_ ? acos(r / target_rho) - max_switch_angle_ +
(-acos(r / target_rho) + (max_switch_angle_ + min_switch_angle_)) *
std::abs(v_yaw) / max_track_target_vel_ :
min_switch_angle_;
is_in_delay_before_switch_ =
((((yaw + v_yaw * (rough_fly_time + config_.delay)) > output_yaw_ + switch_armor_angle) && v_yaw > 0.) ||
(((yaw + v_yaw * (rough_fly_time + config_.delay)) < output_yaw_ - switch_armor_angle) && v_yaw < 0.)) &&
track_target_;
bool is_low_speed = std::abs(v_yaw) < 1.0;
if (((((yaw + v_yaw * rough_fly_time) > output_yaw_ + switch_armor_angle) && v_yaw > 0.) ||
(((yaw + v_yaw * rough_fly_time) < output_yaw_ - switch_armor_angle) && v_yaw < 0.)) &&
!is_low_speed)
{
selected_armor_ = v_yaw > 0. ? -1 : 1;
r = armors_num == 4 ? r2 : r1;
z = armors_num == 4 ? pos.z + dz : pos.z;
count_++;
if (identified_target_change_)
{
count_ = 0;
identified_target_change_ = false;
}
if (count_ >= config_.min_fit_switch_count_)
{
if (count_ == config_.min_fit_switch_count_)
switch_armor_time_ = ros::Time::now();
selected_armor_ = v_yaw > 0. ? -1 : 1;
r = armors_num == 4 ? r2 : r1;
z = armors_num == 4 ? pos.z + dz : pos.z;
}
}
int count{};
double error = 999;
Expand Down Expand Up @@ -180,6 +210,11 @@ bool BulletSolver::solve(geometry_msgs::Point pos, geometry_msgs::Vector3 vel, d
if (count >= 20 || std::isnan(error))
return false;
}
if (fly_time_pub_->trylock())
{
fly_time_pub_->msg_.data = fly_time_;
fly_time_pub_->unlockAndPublish();
}
return true;
}

Expand Down Expand Up @@ -301,6 +336,32 @@ double BulletSolver::getGimbalError(geometry_msgs::Point pos, geometry_msgs::Vec
return error;
}

void BulletSolver::identifiedTargetChangeCB(const std_msgs::BoolConstPtr& msg)
{
if (msg->data)
identified_target_change_ = true;
}

void BulletSolver::judgeShootBeforehand(const ros::Time& time)
{
if (!track_target_)
shoot_beforehand_cmd_ = rm_msgs::ShootBeforehandCmd::JUDGE_BY_ERROR;
else if ((ros::Time::now() - switch_armor_time_).toSec() < ros::Duration(config_.ban_shoot_duration).toSec())
shoot_beforehand_cmd_ = rm_msgs::ShootBeforehandCmd::BAN_SHOOT;
else if (is_in_delay_before_switch_ && selected_armor_ == 0)
shoot_beforehand_cmd_ = rm_msgs::ShootBeforehandCmd::BAN_SHOOT;
else if ((ros::Time::now() - switch_armor_time_).toSec() < ros::Duration(config_.gimbal_switch_duration).toSec())
shoot_beforehand_cmd_ = rm_msgs::ShootBeforehandCmd::ALLOW_SHOOT;
else
shoot_beforehand_cmd_ = rm_msgs::ShootBeforehandCmd::JUDGE_BY_ERROR;
if (shoot_beforehand_cmd_pub_->trylock())
{
shoot_beforehand_cmd_pub_->msg_.stamp = time;
shoot_beforehand_cmd_pub_->msg_.cmd = shoot_beforehand_cmd_;
shoot_beforehand_cmd_pub_->unlockAndPublish();
}
}

void BulletSolver::reconfigCB(rm_gimbal_controllers::BulletSolverConfig& config, uint32_t /*unused*/)
{
ROS_INFO("[Bullet Solver] Dynamic params change");
Expand All @@ -316,6 +377,11 @@ void BulletSolver::reconfigCB(rm_gimbal_controllers::BulletSolverConfig& config,
config.delay = init_config.delay;
config.dt = init_config.dt;
config.timeout = init_config.timeout;
config.ban_shoot_duration = init_config.ban_shoot_duration;
config.gimbal_switch_duration = init_config.gimbal_switch_duration;
config.max_switch_angle_ = init_config.max_switch_angle_;
config.min_switch_angle_ = init_config.min_switch_angle_;
config.min_fit_switch_count_ = init_config.min_fit_switch_count_;
dynamic_reconfig_initialized_ = true;
}
Config config_non_rt{ .resistance_coff_qd_10 = config.resistance_coff_qd_10,
Expand All @@ -326,7 +392,12 @@ void BulletSolver::reconfigCB(rm_gimbal_controllers::BulletSolverConfig& config,
.g = config.g,
.delay = config.delay,
.dt = config.dt,
.timeout = config.timeout };
.timeout = config.timeout,
.ban_shoot_duration = config.ban_shoot_duration,
.gimbal_switch_duration = config.gimbal_switch_duration,
.max_switch_angle_ = config.max_switch_angle_,
.min_switch_angle_ = config.min_switch_angle_,
.min_fit_switch_count_ = config.min_fit_switch_count_ };
config_rt_buffer_.writeFromNonRT(config_non_rt);
}
} // namespace rm_gimbal_controllers
Loading
Loading