Skip to content

Commit

Permalink
Include attitude reference in setpoints (#172)
Browse files Browse the repository at this point in the history
Add support for publishing attitude setpoints
  • Loading branch information
Jaeyoung-Lim authored Feb 27, 2021
1 parent 393242d commit 07d0203
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ class geometricCtrl {
int posehistory_window_;

void pubMotorCommands();
void pubRateCommands(const Eigen::Vector4d &cmd);
void pubRateCommands(const Eigen::Vector4d &cmd, const Eigen::Vector4d &target_attitude);
void pubReferencePose(const Eigen::Vector3d &target_position, const Eigen::Vector4d &target_attitude);
void pubPoseHistory();
void pubSystemStatus();
Expand Down
8 changes: 6 additions & 2 deletions geometric_controller/src/geometric_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -233,7 +233,7 @@ void geometricCtrl::cmdloopCallback(const ros::TimerEvent &event) {
case MISSION_EXECUTION:
if (!feedthrough_enable_) computeBodyRateCmd(cmdBodyRate_, targetPos_, targetVel_, targetAcc_);
pubReferencePose(targetPos_, q_des);
pubRateCommands(cmdBodyRate_);
pubRateCommands(cmdBodyRate_, q_des);
appendPoseHistory();
pubPoseHistory();
break;
Expand Down Expand Up @@ -295,7 +295,7 @@ void geometricCtrl::pubReferencePose(const Eigen::Vector3d &target_position, con
referencePosePub_.publish(msg);
}

void geometricCtrl::pubRateCommands(const Eigen::Vector4d &cmd) {
void geometricCtrl::pubRateCommands(const Eigen::Vector4d &cmd, const Eigen::Vector4d &target_attitude) {
mavros_msgs::AttitudeTarget msg;

msg.header.stamp = ros::Time::now();
Expand All @@ -304,6 +304,10 @@ void geometricCtrl::pubRateCommands(const Eigen::Vector4d &cmd) {
msg.body_rate.y = cmd(1);
msg.body_rate.z = cmd(2);
msg.type_mask = 128; // Ignore orientation messages
msg.orientation.w = target_attitude(0);
msg.orientation.x = target_attitude(1);
msg.orientation.y = target_attitude(2);
msg.orientation.z = target_attitude(3);
msg.thrust = cmd(3);

angularVelPub_.publish(msg);
Expand Down

0 comments on commit 07d0203

Please sign in to comment.