Skip to content

Commit 7aa1dbe

Browse files
authored
Merge branch 'rm-controls:master' into imagetransmission
2 parents 2fd47ee + c5367f9 commit 7aa1dbe

File tree

5 files changed

+46
-28
lines changed

5 files changed

+46
-28
lines changed

rm_common/include/rm_common/decision/power_limit.h

Lines changed: 31 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -86,7 +86,14 @@ class PowerLimit
8686
}
8787
void updateState(uint8_t state)
8888
{
89-
expect_state_ = state;
89+
if (!capacitor_is_on_)
90+
expect_state_ = ALLOFF;
91+
else
92+
expect_state_ = state;
93+
}
94+
void updateCapSwitchState(bool state)
95+
{
96+
capacitor_is_on_ = state;
9097
}
9198
void setGameRobotData(const rm_msgs::GameRobotStatus data)
9299
{
@@ -122,24 +129,29 @@ class PowerLimit
122129
{
123130
if (capacity_is_online_)
124131
{
125-
if (chassis_power_limit_ > burst_power_)
126-
chassis_cmd.power_limit = burst_power_;
132+
if (expect_state_ == ALLOFF)
133+
normal(chassis_cmd);
127134
else
128135
{
129-
switch (is_new_capacitor_ ? expect_state_ : cap_state_)
136+
if (chassis_power_limit_ > burst_power_)
137+
chassis_cmd.power_limit = burst_power_;
138+
else
130139
{
131-
case NORMAL:
132-
normal(chassis_cmd);
133-
break;
134-
case BURST:
135-
burst(chassis_cmd, is_gyro);
136-
break;
137-
case CHARGE:
138-
charge(chassis_cmd);
139-
break;
140-
default:
141-
zero(chassis_cmd);
142-
break;
140+
switch (is_new_capacitor_ ? expect_state_ : cap_state_)
141+
{
142+
case NORMAL:
143+
normal(chassis_cmd);
144+
break;
145+
case BURST:
146+
burst(chassis_cmd, is_gyro);
147+
break;
148+
case CHARGE:
149+
charge(chassis_cmd);
150+
break;
151+
default:
152+
zero(chassis_cmd);
153+
break;
154+
}
143155
}
144156
}
145157
}
@@ -169,7 +181,7 @@ class PowerLimit
169181
}
170182
void burst(rm_msgs::ChassisCmd& chassis_cmd, bool is_gyro)
171183
{
172-
if (cap_energy_ > capacitor_threshold_)
184+
if (cap_state_ != ALLOFF && cap_energy_ > capacitor_threshold_)
173185
{
174186
if (is_gyro)
175187
chassis_cmd.power_limit = chassis_power_limit_ + extra_power_;
@@ -188,8 +200,9 @@ class PowerLimit
188200
double charge_power_{}, extra_power_{}, burst_power_{};
189201
double buffer_threshold_{};
190202
double power_gain_{};
191-
bool is_new_capacitor_{};
203+
bool is_new_capacitor_{ false };
192204
uint8_t expect_state_{}, cap_state_{};
205+
bool capacitor_is_on_{ true };
193206

194207
bool referee_is_online_{ false };
195208
bool capacity_is_online_{ false };

rm_msgs/msg/referee/PowerManagementSampleAndStatusData.msg

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@ float32 chassis_power
22
float32 chassis_expect_power
33
float32 capacity_recent_charge_power
44
float32 capacity_remain_charge
5-
uint8 capacity_expect_charge_power
5+
uint8 capacity_discharge_power
66
uint8 state_machine_running_state
77
uint8 power_management_protection_info
88
uint8 power_management_topology

rm_referee/include/rm_referee/ui/trigger_change_ui.h

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,8 @@ class ChassisTriggerChangeUi : public TriggerChangeUi
7070

7171
private:
7272
void update() override;
73-
void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false) override;
73+
void updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode = 0, bool sub_flag = false,
74+
bool extra_flag = false);
7475
void displayInCapacity();
7576
std::string getChassisState(uint8_t mode);
7677
uint8_t chassis_mode_, power_limit_state_, s_l_, s_r_, key_ctrl_, key_shift_, key_b_;

rm_referee/src/referee.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -551,7 +551,7 @@ int Referee::unpack(uint8_t* rx_data)
551551
(static_cast<uint16_t>((data[4] << 8) | data[5]) / 100.);
552552
sample_and_status_pub_data.capacity_remain_charge =
553553
(static_cast<uint16_t>((data[6] << 8) | data[7]) / 10000.);
554-
sample_and_status_pub_data.capacity_expect_charge_power = static_cast<uint8_t>(data[8]);
554+
sample_and_status_pub_data.capacity_discharge_power = static_cast<uint8_t>(data[8]);
555555
sample_and_status_pub_data.state_machine_running_state = base_.capacity_recent_mode_ =
556556
static_cast<uint8_t>(data[9] >> 4);
557557
sample_and_status_pub_data.power_management_protection_info = static_cast<uint8_t>((data[9] >> 2) & 0x03);

rm_referee/src/ui/trigger_change_ui.cpp

Lines changed: 11 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -87,7 +87,8 @@ void ChassisTriggerChangeUi::update()
8787
updateConfig(chassis_mode_, false, 1, false);
8888
else
8989
updateConfig(chassis_mode_, power_limit_state_ == rm_common::PowerLimit::BURST, 0,
90-
power_limit_state_ == rm_common::PowerLimit::CHARGE);
90+
power_limit_state_ == rm_common::PowerLimit::CHARGE,
91+
power_limit_state_ == rm_common::PowerLimit::NORMAL);
9192
graph_->setOperation(rm_referee::GraphOperation::UPDATE);
9293
checkModeChange();
9394
updateTwiceForQueue(true);
@@ -128,7 +129,8 @@ void ChassisTriggerChangeUi::checkModeChange()
128129
}
129130
}
130131

131-
void ChassisTriggerChangeUi::updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode, bool sub_flag)
132+
void ChassisTriggerChangeUi::updateConfig(uint8_t main_mode, bool main_flag, uint8_t sub_mode, bool sub_flag,
133+
bool extra_flag)
132134
{
133135
static ros::Time trigger_time;
134136
static int expect;
@@ -144,9 +146,7 @@ void ChassisTriggerChangeUi::updateConfig(uint8_t main_mode, bool main_flag, uin
144146
graph_->setColor(rm_referee::GraphColor::PINK);
145147
else
146148
{
147-
if ((base_.capacity_recent_mode_ == rm_common::PowerLimit::NORMAL ||
148-
power_limit_state_ == rm_common::PowerLimit::NORMAL) &&
149-
!delay)
149+
if (base_.capacity_recent_mode_ == rm_common::PowerLimit::ALLOFF && !delay)
150150
{
151151
trigger_time = ros::Time::now();
152152
expect = power_limit_state_;
@@ -165,8 +165,10 @@ void ChassisTriggerChangeUi::updateConfig(uint8_t main_mode, bool main_flag, uin
165165
graph_->setColor(rm_referee::GraphColor::ORANGE);
166166
else if (sub_flag)
167167
graph_->setColor(rm_referee::GraphColor::GREEN);
168-
else
168+
else if (extra_flag)
169169
graph_->setColor(rm_referee::GraphColor::WHITE);
170+
else
171+
graph_->setColor(rm_referee::GraphColor::BLACK);
170172
delay = false;
171173
}
172174
}
@@ -176,8 +178,10 @@ void ChassisTriggerChangeUi::updateConfig(uint8_t main_mode, bool main_flag, uin
176178
graph_->setColor(rm_referee::GraphColor::ORANGE);
177179
else if (sub_flag)
178180
graph_->setColor(rm_referee::GraphColor::GREEN);
179-
else
181+
else if (extra_flag)
180182
graph_->setColor(rm_referee::GraphColor::WHITE);
183+
else
184+
graph_->setColor(rm_referee::GraphColor::BLACK);
181185
}
182186
}
183187
}

0 commit comments

Comments
 (0)