Skip to content

Commit

Permalink
Merge pull request #74 from 1moule/modify_key
Browse files Browse the repository at this point in the history
Modify some key logic and add function of adjusting friction wheel speed by key
  • Loading branch information
ye-luo-xi-tui authored Aug 2, 2023
2 parents e6c208a + 2449f61 commit 467958a
Show file tree
Hide file tree
Showing 3 changed files with 30 additions and 21 deletions.
2 changes: 1 addition & 1 deletion include/rm_manual/balance_manual.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,13 @@ class BalanceManual : public ChassisGimbalShooterCoverManual
void sPressing() override;
void dPressing() override;
void bPress() override;
void vPress() override;
void ctrlZPress() override;
void rightSwitchDownRise() override;
void rightSwitchMidRise() override;

void sendCommand(const ros::Time& time) override;
void checkKeyboard(const rm_msgs::DbusData::ConstPtr& dbus_data) override;
void vPress();
void ctrlXPress();
void modeFallen(ros::Duration duration);
void modeNormalize();
Expand Down
18 changes: 9 additions & 9 deletions include/rm_manual/chassis_gimbal_shooter_manual.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,10 +76,11 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual
void aRelease() override;
void sRelease() override;
void dRelease() override;

virtual void gPress();
virtual void vPress();
virtual void xPress();
virtual void ePress();
virtual void eRelease();
virtual void cPress();
virtual void bPress();
virtual void rPress();
Expand All @@ -88,10 +89,11 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual
virtual void shiftRelease();
void qPress()
{
if (shooter_cmd_sender_->getShootFrequency() != rm_common::HeatLimit::LOW)
shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::LOW);
else
shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::BURST);
shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::BURST);
}
void qRelease()
{
shooter_cmd_sender_->setShootFrequency(rm_common::HeatLimit::LOW);
}
void fPress()
{
Expand All @@ -103,8 +105,8 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual
virtual void ctrlQPress();

InputEvent self_inspection_event_, game_start_event_, e_event_, c_event_, g_event_, q_event_, f_event_, b_event_,
x_event_, r_event_, ctrl_v_event_, ctrl_b_event_, ctrl_q_event_, ctrl_r_event_, shift_event_, ctrl_shift_b_event_,
mouse_left_event_, mouse_right_event_;
x_event_, r_event_, v_event_, ctrl_v_event_, ctrl_b_event_, ctrl_q_event_, ctrl_r_event_, shift_event_,
ctrl_shift_b_event_, mouse_left_event_, mouse_right_event_;
rm_common::ShooterCommandSender* shooter_cmd_sender_{};
rm_common::CameraSwitchCommandSender* camera_switch_cmd_sender_{};
rm_common::JointPositionBinaryCommandSender* scope_cmd_sender_{};
Expand All @@ -116,8 +118,6 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual

geometry_msgs::PointStamped point_out_;

uint8_t last_det_color_{};

bool prepare_shoot_ = false, turn_flag_ = false, is_balance_ = false, use_scope_ = false,
adjust_image_transmission_ = false;
double yaw_current_{};
Expand Down
31 changes: 20 additions & 11 deletions src/chassis_gimbal_shooter_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,15 +41,18 @@ ChassisGimbalShooterManual::ChassisGimbalShooterManual(ros::NodeHandle& nh, ros:
game_start_event_.setRising(boost::bind(&ChassisGimbalShooterManual::gameStart, this));
left_switch_up_event_.setActiveHigh(boost::bind(&ChassisGimbalShooterManual::leftSwitchUpOn, this, _1));
left_switch_mid_event_.setActiveHigh(boost::bind(&ChassisGimbalShooterManual::leftSwitchMidOn, this, _1));
e_event_.setRising(boost::bind(&ChassisGimbalShooterManual::ePress, this));
e_event_.setEdge(boost::bind(&ChassisGimbalShooterManual::ePress, this),
boost::bind(&ChassisGimbalShooterManual::eRelease, this));
c_event_.setRising(boost::bind(&ChassisGimbalShooterManual::cPress, this));
q_event_.setRising(boost::bind(&ChassisGimbalShooterManual::qPress, this));
q_event_.setEdge(boost::bind(&ChassisGimbalShooterManual::qPress, this),
boost::bind(&ChassisGimbalShooterManual::qRelease, this));
f_event_.setRising(boost::bind(&ChassisGimbalShooterManual::fPress, this));
b_event_.setRising(boost::bind(&ChassisGimbalShooterManual::bPress, this));
x_event_.setRising(boost::bind(&ChassisGimbalShooterManual::xPress, this));
x_event_.setActiveLow(boost::bind(&ChassisGimbalShooterManual::xReleasing, this));
r_event_.setRising(boost::bind(&ChassisGimbalShooterManual::rPress, this));
g_event_.setRising(boost::bind(&ChassisGimbalShooterManual::gPress, this));
v_event_.setRising(boost::bind(&ChassisGimbalShooterManual::vPress, this));
ctrl_v_event_.setRising(boost::bind(&ChassisGimbalShooterManual::ctrlVPress, this));
ctrl_b_event_.setRising(boost::bind(&ChassisGimbalShooterManual::ctrlBPress, this));
ctrl_q_event_.setRising(boost::bind(&ChassisGimbalShooterManual::ctrlQPress, this));
Expand Down Expand Up @@ -92,6 +95,7 @@ void ChassisGimbalShooterManual::checkKeyboard(const rm_msgs::DbusData::ConstPtr
b_event_.update((!dbus_data->key_ctrl && !dbus_data->key_shift) & dbus_data->key_b);
x_event_.update(dbus_data->key_x & !dbus_data->key_ctrl);
r_event_.update((!dbus_data->key_ctrl) & dbus_data->key_r);
v_event_.update((!dbus_data->key_ctrl) & dbus_data->key_v);
ctrl_v_event_.update(dbus_data->key_ctrl & dbus_data->key_v);
ctrl_b_event_.update(dbus_data->key_ctrl & dbus_data->key_b & !dbus_data->key_shift);
ctrl_q_event_.update(dbus_data->key_ctrl & dbus_data->key_q);
Expand Down Expand Up @@ -358,7 +362,14 @@ void ChassisGimbalShooterManual::mouseRightPress()

void ChassisGimbalShooterManual::ePress()
{
switch_armor_target_srv_->switchArmorTargetType();
switch_armor_target_srv_->setArmorTargetType(rm_msgs::StatusChangeRequest::ARMOR_OUTPOST_BASE);
switch_armor_target_srv_->callService();
shooter_cmd_sender_->setArmorType(switch_armor_target_srv_->getArmorTarget());
}

void ChassisGimbalShooterManual::eRelease()
{
switch_armor_target_srv_->setArmorTargetType(rm_msgs::StatusChangeRequest::ARMOR_ALL);
switch_armor_target_srv_->callService();
shooter_cmd_sender_->setArmorType(switch_armor_target_srv_->getArmorTarget());
}
Expand Down Expand Up @@ -407,14 +418,7 @@ void ChassisGimbalShooterManual::rPress()

void ChassisGimbalShooterManual::gPress()
{
if (switch_detection_srv_->getColor() != rm_msgs::StatusChangeRequest::PURPLE)
{
last_det_color_ = switch_detection_srv_->getColor();
switch_detection_srv_->setColor(rm_msgs::StatusChangeRequest::PURPLE);
}
else
switch_detection_srv_->setColor(last_det_color_);
switch_detection_srv_->callService();
shooter_cmd_sender_->dropSpeed();
}

void ChassisGimbalShooterManual::wPress()
Expand Down Expand Up @@ -550,6 +554,11 @@ void ChassisGimbalShooterManual::xReleasing()
}
}

void ChassisGimbalShooterManual::vPress()
{
shooter_cmd_sender_->raiseSpeed();
}

void ChassisGimbalShooterManual::shiftPress()
{
chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::BURST);
Expand Down

0 comments on commit 467958a

Please sign in to comment.