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
2 changes: 1 addition & 1 deletion src/chassis_gimbal_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ void ChassisGimbalManual::updateRc(const rm_msgs::DbusData::ConstPtr& dbus_data)
void ChassisGimbalManual::updatePc(const rm_msgs::DbusData::ConstPtr& dbus_data)
{
ManualBase::updatePc(dbus_data);
gimbal_cmd_sender_->setRate(-dbus_data->m_x * gimbal_scale_, dbus_data->m_y * gimbal_scale_);
gimbal_cmd_sender_->setRate(-dbus_data->m_x * gimbal_scale_, -dbus_data->m_y * gimbal_scale_);
if (gimbal_cmd_sender_->getMsg()->mode == rm_msgs::GimbalCmd::RATE)
chassis_cmd_sender_->setFollowVelDes(gimbal_cmd_sender_->getMsg()->rate_yaw);
else
Expand Down
22 changes: 16 additions & 6 deletions src/chassis_gimbal_shooter_manual.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -235,6 +235,7 @@ void ChassisGimbalShooterManual::remoteControlTurnOff()
up_change_position_ = false;
low_change_position_ = false;
need_change_position_ = false;
deployed_ = false;
}

void ChassisGimbalShooterManual::remoteControlTurnOn()
Expand All @@ -256,6 +257,7 @@ void ChassisGimbalShooterManual::robotDie()
up_change_position_ = false;
low_change_position_ = false;
need_change_position_ = false;
deployed_ = false;
}

void ChassisGimbalShooterManual::chassisOutputOn()
Expand Down Expand Up @@ -317,6 +319,15 @@ void ChassisGimbalShooterManual::updatePc(const rm_msgs::DbusData::ConstPtr& dbu
traj_pitch_ += traj_scale_ * gimbal_cmd_sender_->getMsg()->rate_pitch * ros::Duration(0.01).toSec();
gimbal_cmd_sender_->setGimbalTraj(traj_yaw_, traj_pitch_);
}
if ((gimbal_cmd_sender_->getMsg()->mode == rm_msgs::GimbalCmd::TRAJ && deployed_) &&
std::sqrt(std::pow(vel_cmd_sender_->getMsg()->linear.x, 2) + std::pow(vel_cmd_sender_->getMsg()->linear.y, 2)) >
0.0)
{
setChassisMode(rm_msgs::ChassisCmd::FOLLOW);
gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::RATE);
deployed_ = false;
shooter_cmd_sender_->setDeployState(false);
}
}

void ChassisGimbalShooterManual::rightSwitchDownRise()
Expand Down Expand Up @@ -615,7 +626,7 @@ void ChassisGimbalShooterManual::vPress()

void ChassisGimbalShooterManual::zPress()
{
if (chassis_cmd_sender_->getMsg()->mode != rm_msgs::ChassisCmd::RAW && !is_gyro_)
if (chassis_cmd_sender_->getMsg()->mode != rm_msgs::ChassisCmd::RAW && !deployed_)
{
double roll{}, pitch{}, yaw{};
try
Expand All @@ -628,25 +639,23 @@ void ChassisGimbalShooterManual::zPress()
}
gimbal_cmd_sender_->setGimbalTrajFrameId("base_link");
gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::TRAJ);
traj_yaw_ = yaw, traj_pitch_ = -0.40;
traj_yaw_ = yaw, traj_pitch_ = -0.585;
gimbal_cmd_sender_->setGimbalTraj(traj_yaw_, traj_pitch_);
setChassisMode(rm_msgs::ChassisCmd::DEPLOY);
shooter_cmd_sender_->deploySpeed();
shooter_cmd_sender_->setDeployState(true);
deployed_ = true;
}
else
{
setChassisMode(rm_msgs::ChassisCmd::FOLLOW);
gimbal_cmd_sender_->setMode(rm_msgs::GimbalCmd::RATE);
shooter_cmd_sender_->exitDeploySpeed();
shooter_cmd_sender_->setDeployState(false);
deployed_ = false;
}
}

void ChassisGimbalShooterManual::shiftPress()
{
if (chassis_cmd_sender_->getMsg()->mode != rm_msgs::ChassisCmd::FOLLOW && is_gyro_)
setChassisMode(rm_msgs::ChassisCmd::FOLLOW);
chassis_cmd_sender_->power_limit_->updateState(rm_common::PowerLimit::BURST);
}

Expand Down Expand Up @@ -703,6 +712,7 @@ void ChassisGimbalShooterManual::ctrlQPress()
{
shooter_calibration_->reset();
gimbal_calibration_->reset();
adjust_image_transmission_ = false;
up_change_position_ = false;
low_change_position_ = false;
need_change_position_ = false;
Expand Down