Skip to content

Commit

Permalink
Merge pull request #164 from liyixin135/traj
Browse files Browse the repository at this point in the history
Add TRAJ mode for gimbal
  • Loading branch information
d0h0s authored Jul 28, 2024
2 parents e688d53 + 867c5d7 commit 2f23f4b
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 1 deletion.
Original file line number Diff line number Diff line change
Expand Up @@ -142,6 +142,7 @@ class Controller : public controller_interface::MultiInterfaceController<rm_cont
void rate(const ros::Time& time, const ros::Duration& period);
void track(const ros::Time& time);
void direct(const ros::Time& time);
void traj(const ros::Time& time);
bool setDesIntoLimit(double& real_des, double current_des, double base2gimbal_current_des,
const urdf::JointConstSharedPtr& joint_urdf);
void moveJoint(const ros::Time& time, const ros::Duration& period);
Expand Down Expand Up @@ -199,7 +200,8 @@ class Controller : public controller_interface::MultiInterfaceController<rm_cont
{
RATE,
TRACK,
DIRECT
DIRECT,
TRAJ
};
int state_ = RATE;
};
Expand Down
13 changes: 13 additions & 0 deletions rm_gimbal_controllers/src/gimbal_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,6 +192,9 @@ void Controller::update(const ros::Time& time, const ros::Duration& period)
case DIRECT:
direct(time);
break;
case TRAJ:
traj(time);
break;
}
moveJoint(time, period);
}
Expand Down Expand Up @@ -356,6 +359,16 @@ void Controller::direct(const ros::Time& time)
setDes(time, yaw, pitch);
}

void Controller::traj(const ros::Time& time)
{
if (state_changed_)
{ // on enter
state_changed_ = false;
ROS_INFO("[Gimbal] Enter TRAJ");
}
setDes(time, cmd_gimbal_.traj_yaw, cmd_gimbal_.traj_pitch);
}

bool Controller::setDesIntoLimit(double& real_des, double current_des, double base2gimbal_current_des,
const urdf::JointConstSharedPtr& joint_urdf)
{
Expand Down

0 comments on commit 2f23f4b

Please sign in to comment.