Skip to content
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
4 changes: 0 additions & 4 deletions .github/workflows/format.yml
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,4 @@ jobs:
steps:
- uses: actions/checkout@v3
- uses: actions/setup-python@v3
- name: Install clang-format
run: |
sudo apt update
sudo apt install clang-format
- uses: pre-commit/action@v3.0.0
10 changes: 3 additions & 7 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -39,12 +39,8 @@ repos:
- id: rst-linter
exclude: .*/doc/.*

- repo: local
- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v14.0.6
hooks:
- id: clang-format
name: clang-format
description: Format files with ClangFormat.
entry: clang-format
language: system
files: \.(c|cc|cxx|cpp|frag|glsl|h|hpp|hxx|ih|ispc|ipp|java|js|m|proto|vert)$
args: [ "-fallback-style=none", "-i" ]
args: [ "-fallback-style=none" ]
30 changes: 30 additions & 0 deletions rm_common/include/rm_common/decision/command_sender.h
Original file line number Diff line number Diff line change
Expand Up @@ -306,11 +306,31 @@ class ChassisActiveSuspensionCommandSender : public TimeStampCommandSenderBase<r
explicit ChassisActiveSuspensionCommandSender(ros::NodeHandle& nh)
: TimeStampCommandSenderBase<rm_msgs::ChassisActiveSusCmd>(nh)
{
nh.param("leg_feedforward_duration", leg_feedforward_duration_, 20.0);
}
void setLegSwitchTime(ros::Time leg_switch_time)
{
leg_switch_time_ = leg_switch_time;
}
int getLegMode()
{
return msg_.mode;
}
void sendCommand(const ros::Time& time) override
{
msg_.feedforward_countdown =
std::max(0, static_cast<int>(leg_feedforward_duration_ - (ros::Time::now() - leg_switch_time_).toSec()));
TimeStampCommandSenderBase<rm_msgs::ChassisActiveSusCmd>::sendCommand(time);
}
void setZero() override
{
msg_.mode = 0;
msg_.feedforward_countdown = 0;
}

private:
double leg_feedforward_duration_{};
ros::Time leg_switch_time_{};
};
class GimbalCommandSender : public TimeStampCommandSenderBase<rm_msgs::GimbalCmd>
{
Expand Down Expand Up @@ -516,6 +536,7 @@ class ShooterCommandSender : public TimeStampCommandSenderBase<rm_msgs::ShootCmd
}
void sendCommand(const ros::Time& time) override
{
msg_.allow_deploy_fire = getDeployAllowFireFlag();
msg_.wheel_speed = getWheelSpeedDes();
msg_.wheels_speed_offset_front = getFrontWheelSpeedOffset();
msg_.wheels_speed_offset_back = getBackWheelSpeedOffset();
Expand Down Expand Up @@ -591,6 +612,14 @@ class ShooterCommandSender : public TimeStampCommandSenderBase<rm_msgs::ShootCmd
}
}
}
void setDeployAllowFireFlag(bool flag)
{
allow_deploy_fire_ = flag;
}
bool getDeployAllowFireFlag()
{
return allow_deploy_fire_;
}
double getFrontWheelSpeedOffset()
{
wheels_speed_offset_front_ = wheel_speed_offset_front_;
Expand Down Expand Up @@ -656,6 +685,7 @@ class ShooterCommandSender : public TimeStampCommandSenderBase<rm_msgs::ShootCmd
bool auto_wheel_speed_ = false;
bool hero_flag_{};
bool deploy_flag_ = false;
bool allow_deploy_fire_ = false;
rm_msgs::TrackData track_data_;
rm_msgs::GimbalDesError gimbal_des_error_;
rm_msgs::ShootBeforehandCmd shoot_beforehand_cmd_;
Expand Down
147 changes: 80 additions & 67 deletions rm_common/include/rm_common/decision/power_limit.h
Original file line number Diff line number Diff line change
Expand Up @@ -59,32 +59,32 @@ class PowerLimit
ROS_ERROR("Safety power no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("capacitor_threshold", capacitor_threshold_))
ROS_ERROR("Capacitor threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("disable_cap_gyro_threshold", disable_cap_gyro_threshold_))
ROS_ERROR("Disable cap gyro threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("enable_cap_gyro_threshold", enable_cap_gyro_threshold_))
ROS_ERROR("Enable cap gyro threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("disable_use_cap_threshold", disable_use_cap_threshold_))
ROS_ERROR("Disable use cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("enable_use_cap_threshold", enable_use_cap_threshold_))
ROS_ERROR("Enable use cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("charge_power", charge_power_))
ROS_ERROR("Charge power no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("disable_burst_cap_threshold", disable_burst_cap_threshold_))
ROS_ERROR("Disable burst cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("enable_burst_cap_threshold", enable_burst_cap_threshold_))
ROS_ERROR("Enable burst cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("disable_normal_cap_threshold", disable_normal_cap_threshold_))
ROS_ERROR("Disable normal cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("enable_gyro_cap_threshold", enable_gyro_cap_threshold_))
ROS_ERROR("Enable gyro cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("disable_gyro_cap_threshold", disable_gyro_cap_threshold_))
ROS_ERROR("Disable gyro cap threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("extra_power", extra_power_))
ROS_ERROR("Extra power no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("burst_power", burst_power_))
ROS_ERROR("Burst power no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("standard_power", standard_power_))
ROS_ERROR("Standard power no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("gyro_power", gyro_power_))
ROS_ERROR("Gyro power no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("upstairs_power", upstairs_power_))
ROS_ERROR("Upstairs power no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("max_power_limit", max_power_limit_))
ROS_ERROR("max power limit no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("power_gain", power_gain_))
ROS_ERROR("power gain no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("buffer_threshold", buffer_threshold_))
ROS_ERROR("buffer threshold no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("is_new_capacitor", is_new_capacitor_))
ROS_ERROR("is_new_capacitor no defined (namespace: %s)", nh.getNamespace().c_str());
if (!nh.getParam("total_burst_time", total_burst_time_))
ROS_ERROR("total burst time no defined (namespace: %s)", nh.getNamespace().c_str());
default_max_power_limit_ = max_power_limit_;
default_burst_power_ = burst_power_;
}
typedef enum
{
Expand All @@ -103,14 +103,7 @@ class PowerLimit
}
void updateState(uint8_t state)
{
if (!capacitor_is_on_)
expect_state_ = ALLOFF;
else
expect_state_ = state;
}
void updateCapSwitchState(bool state)
{
capacitor_is_on_ = state;
expect_state_ = state;
}
void setGameRobotData(const rm_msgs::GameRobotStatus data)
{
Expand All @@ -120,7 +113,6 @@ class PowerLimit
void setChassisPowerBuffer(const rm_msgs::PowerHeatData data)
{
chassis_power_buffer_ = data.chassis_power_buffer;
power_buffer_threshold_ = chassis_power_buffer_ * 0.8;
}
void setCapacityData(const rm_msgs::PowerManagementSampleAndStatusData data)
{
Expand All @@ -136,47 +128,61 @@ class PowerLimit
{
start_burst_time_ = start_burst_time;
}
inline void setBurstPowerLimit(const double& burst_power_limit)
{
burst_power_ = burst_power_limit;
}
ros::Time getStartBurstTime() const
{
return start_burst_time_;
}
inline void setBurstPowerLimit(const double& burst_power_limit)
{
burst_power_ = burst_power_limit;
}
uint8_t getState()
{
return expect_state_;
}

void setUpstairsPower(bool upstairs)
{
if (upstairs)
{
max_power_limit_ = upstairs_power_;
burst_power_ = upstairs_power_;
}
else
{
max_power_limit_ = default_max_power_limit_;
burst_power_ = default_burst_power_;
}
}

void setGyroPower(rm_msgs::ChassisCmd& chassis_cmd)
{
if (!allow_gyro_cap_ && cap_energy_ >= enable_cap_gyro_threshold_)
if (!allow_gyro_cap_ && cap_energy_ >= enable_gyro_cap_threshold_)
allow_gyro_cap_ = true;
if (allow_gyro_cap_ && cap_energy_ <= disable_cap_gyro_threshold_)
if (allow_gyro_cap_ && cap_energy_ <= disable_gyro_cap_threshold_)
allow_gyro_cap_ = false;
if (allow_gyro_cap_ && chassis_power_limit_ < 80)
chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
if (allow_gyro_cap_)
{
chassis_cmd.power_limit = gyro_power_;
}
else
normal(chassis_cmd);
// expect_state_ = NORMAL;
expect_state_ = NORMAL;
}

void setBurstPower(rm_msgs::ChassisCmd& chassis_cmd)
{
if (!allow_use_cap_ && cap_energy_ >= enable_use_cap_threshold_)
if (!allow_use_cap_ && cap_energy_ >= enable_burst_cap_threshold_)
allow_use_cap_ = true;
if (allow_use_cap_ && cap_energy_ <= disable_use_cap_threshold_)
if (allow_use_cap_ && cap_energy_ <= disable_burst_cap_threshold_)
allow_use_cap_ = false;
if (allow_use_cap_)
{
if (ros::Time::now() - start_burst_time_ < ros::Duration(total_burst_time_))
chassis_cmd.power_limit = burst_power_;
else
chassis_cmd.power_limit = standard_power_;
chassis_cmd.power_limit = burst_power_;
}
else
normal(chassis_cmd);
// expect_state_ = NORMAL;
expect_state_ = NORMAL;
}

void setLimitPower(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
{
if (robot_id_ == rm_msgs::GameRobotStatus::BLUE_ENGINEER || robot_id_ == rm_msgs::GameRobotStatus::RED_ENGINEER)
Expand All @@ -191,7 +197,7 @@ class PowerLimit
chassis_cmd.power_limit = burst_power_;
else
{
switch (is_new_capacitor_ ? expect_state_ : cap_state_)
switch (expect_state_)
{
case NORMAL:
normal(chassis_cmd);
Expand Down Expand Up @@ -223,39 +229,45 @@ class PowerLimit
allow_use_cap_ = false;
chassis_cmd.power_limit = chassis_power_limit_ * 0.70;
}

void normal(rm_msgs::ChassisCmd& chassis_cmd)
{
if (is_new_capacitor_)
allow_use_cap_ = false;
if (cap_state_ != ALLOFF && cap_energy_ > disable_normal_cap_threshold_ &&
chassis_power_buffer_ > power_buffer_threshold_)
{
chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
}
else
{
chassis_cmd.power_limit = chassis_power_limit_;
return;
}
allow_use_cap_ = false;
double buffer_energy_error = chassis_power_buffer_ - buffer_threshold_;
double plus_power = buffer_energy_error * power_gain_;
chassis_cmd.power_limit = chassis_power_limit_ + plus_power;
// TODO:Add protection when buffer<5
if (chassis_cmd.power_limit > max_power_limit_)
{
chassis_cmd.power_limit = max_power_limit_;
}
}

void zero(rm_msgs::ChassisCmd& chassis_cmd)
{
chassis_cmd.power_limit = 0.0;
}

void burst(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
{
if (cap_state_ != ALLOFF && cap_energy_ > capacitor_threshold_ && chassis_power_buffer_ > power_buffer_threshold_)
{
if (is_new_capacitor_)
chassis_cmd.power_limit = burst_power_;
else if (is_gyro)
if (is_gyro)
{
setGyroPower(chassis_cmd);
}
else
{
setBurstPower(chassis_cmd);
}
}
else
normal(chassis_cmd);
// expect_state_ = NORMAL;
expect_state_ = NORMAL;
}

void applyPosturePowerScale(rm_msgs::ChassisCmd& chassis_cmd) const
Expand All @@ -265,21 +277,22 @@ class PowerLimit
chassis_cmd.power_limit = std::max(0.0, std::floor(chassis_cmd.power_limit * posture_power_scale_));
}

int chassis_power_buffer_;
int robot_id_, chassis_power_limit_;
int max_power_limit_{ 70 };
float cap_energy_;
uint8_t expect_state_{}, cap_state_{};

int chassis_power_buffer_{};
int robot_id_{}, chassis_power_limit_{};
double max_power_limit_{ 70.0 };
float cap_energy_{};
double safety_power_{};
double capacitor_threshold_{};
double power_buffer_threshold_{ 50.0 };
double enable_cap_gyro_threshold_{}, disable_cap_gyro_threshold_{}, enable_use_cap_threshold_{},
disable_use_cap_threshold_{};
double charge_power_{}, extra_power_{}, burst_power_{}, standard_power_{};
double buffer_threshold_{};
double enable_burst_cap_threshold_{}, disable_burst_cap_threshold_{};
double enable_gyro_cap_threshold_{}, disable_gyro_cap_threshold_{};
double disable_normal_cap_threshold_{};
double extra_power_{}, burst_power_{}, gyro_power_{}, upstairs_power_{};
double default_max_power_limit_{}, default_burst_power_{};
double power_gain_{};
bool is_new_capacitor_{ false };
uint8_t expect_state_{}, cap_state_{};
bool capacitor_is_on_{ true };

bool allow_gyro_cap_{ false }, allow_use_cap_{ false };
double posture_power_scale_{ 1.0 };

Expand Down
Loading
Loading