Skip to content

Commit

Permalink
Merge branch 'rm-controls:master' into new_dbus
Browse files Browse the repository at this point in the history
  • Loading branch information
YoujianWu authored Mar 31, 2024
2 parents 9001558 + a7f7ab6 commit f6bebed
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 3 deletions.
1 change: 1 addition & 0 deletions include/rm_manual/chassis_gimbal_shooter_manual.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,7 @@ class ChassisGimbalShooterManual : public ChassisGimbalManual
virtual void eRelease();
virtual void cPress();
virtual void bPress();
virtual void bRelease();
virtual void rPress();
virtual void xReleasing();
virtual void shiftPress();
Expand Down
13 changes: 10 additions & 3 deletions src/chassis_gimbal_shooter_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,8 @@ ChassisGimbalShooterManual::ChassisGimbalShooterManual(ros::NodeHandle& nh, ros:
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));
b_event_.setEdge(boost::bind(&ChassisGimbalShooterManual::bPress, this),
boost::bind(&ChassisGimbalShooterManual::bRelease, 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));
Expand Down Expand Up @@ -399,6 +400,11 @@ void ChassisGimbalShooterManual::bPress()
chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::CHARGE);
}

void ChassisGimbalShooterManual::bRelease()
{
chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::NORMAL);
}

void ChassisGimbalShooterManual::rPress()
{
if (camera_switch_cmd_sender_)
Expand Down Expand Up @@ -561,10 +567,11 @@ void ChassisGimbalShooterManual::vPress()

void ChassisGimbalShooterManual::shiftPress()
{
if (chassis_cmd_sender_->getMsg()->mode != rm_msgs::ChassisCmd::FOLLOW)
if (chassis_cmd_sender_->getMsg()->mode != rm_msgs::ChassisCmd::FOLLOW && is_gyro_)
{
chassis_cmd_sender_->setMode(rm_msgs::ChassisCmd::FOLLOW);
vel_cmd_sender_->setAngularZVel(0.);
vel_cmd_sender_->setAngularZVel(1.0);
is_gyro_ = false;
}
chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::BURST);
}
Expand Down

0 comments on commit f6bebed

Please sign in to comment.