Skip to content

Commit 8607788

Browse files
authored
Merge pull request #79 from Jaeyoung-Lim/pr-display-path
Publish mav path
2 parents 21753c1 + 3e35965 commit 8607788

File tree

3 files changed

+68
-4
lines changed

3 files changed

+68
-4
lines changed

geometric_controller/include/geometric_controller/geometric_controller.h

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@ class geometricCtrl
4949
ros::Subscriber yawreferenceSub_;
5050
ros::Publisher rotorVelPub_, angularVelPub_, target_pose_pub_;
5151
ros::Publisher referencePosePub_;
52+
ros::Publisher posehistoryPub_;
5253
ros::ServiceClient arming_client_;
5354
ros::ServiceClient set_mode_client_;
5455
ros::ServiceServer ctrltriggerServ_;
@@ -74,6 +75,7 @@ class geometricCtrl
7475
mavros_msgs::CommandBool arm_cmd_;
7576
mavros_msgs::AttitudeTarget angularVelMsg_;
7677
geometry_msgs::PoseStamped referencePoseMsg_;
78+
std::vector<geometry_msgs::PoseStamped> posehistory_vector_;
7779

7880
Eigen::Vector3d targetPos_, targetVel_, targetAcc_, targetJerk_, targetSnap_, targetPos_prev_, targetVel_prev_;
7981
Eigen::Vector3d mavPos_, mavVel_, mavRate_;
@@ -86,10 +88,13 @@ class geometricCtrl
8688
Eigen::Vector3d errorPos_, errorVel_;
8789
double tau_x, tau_y, tau_z;
8890
double Kpos_x_, Kpos_y_, Kpos_z_, Kvel_x_, Kvel_y_, Kvel_z_;
91+
int posehistory_window_;
8992

9093
void pubMotorCommands();
9194
void pubRateCommands();
9295
void pubReferencePose();
96+
void pubPoseHistory();
97+
void appendPoseHistory();
9398
void odomCallback(const nav_msgs::OdometryConstPtr& odomMsg);
9499
void targetCallback(const geometry_msgs::TwistStamped& msg);
95100
void flattargetCallback(const controller_msgs::FlatTarget& msg);

geometric_controller/launch/config_file.rviz

Lines changed: 27 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,9 @@ Panels:
1010
- /Pose1
1111
- /Pose2
1212
- /Path1
13+
- /Path2
1314
Splitter Ratio: 0.5
14-
Tree Height: 775
15+
Tree Height: 768
1516
- Class: rviz/Selection
1617
Name: Selection
1718
- Class: rviz/Tool Properties
@@ -105,6 +106,29 @@ Visualization Manager:
105106
Topic: /trajectory_publisher/trajectory
106107
Unreliable: false
107108
Value: true
109+
- Alpha: 1
110+
Buffer Length: 1
111+
Class: rviz/Path
112+
Color: 0; 0; 255
113+
Enabled: true
114+
Head Diameter: 0.300000012
115+
Head Length: 0.200000003
116+
Length: 0.300000012
117+
Line Style: Lines
118+
Line Width: 0.0299999993
119+
Name: Path
120+
Offset:
121+
X: 0
122+
Y: 0
123+
Z: 0
124+
Pose Color: 255; 85; 255
125+
Pose Style: None
126+
Radius: 0.0299999993
127+
Shaft Diameter: 0.100000001
128+
Shaft Length: 0.100000001
129+
Topic: /geometric_controller/path
130+
Unreliable: false
131+
Value: true
108132
Enabled: true
109133
Global Options:
110134
Background Color: 48; 48; 48
@@ -156,7 +180,7 @@ Window Geometry:
156180
Height: 1056
157181
Hide Left Dock: false
158182
Hide Right Dock: false
159-
QMainWindow State: 000000ff00000000fd00000004000000000000016a00000396fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000006100fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000396000000d700fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000396fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000396000000ad00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d00650100000000000007800000030000fffffffb0000000800540069006d00650100000000000004500000000000000000000004fb0000039600000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
183+
QMainWindow State: 000000ff00000000fd00000004000000000000016a00000388fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003a00000388000000c600fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000388fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003a000003880000009e00fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000007800000003efc0100000002fb0000000800540069006d00650100000000000007800000024400fffffffb0000000800540069006d00650100000000000004500000000000000000000004fb0000038800000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
160184
Selection:
161185
collapsed: false
162186
Time:
@@ -166,5 +190,5 @@ Window Geometry:
166190
Views:
167191
collapsed: false
168192
Width: 1920
169-
X: 0
193+
X: 65
170194
Y: 24

geometric_controller/src/geometric_controller.cpp

Lines changed: 36 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@ geometricCtrl::geometricCtrl(const ros::NodeHandle& nh, const ros::NodeHandle& n
2828
angularVelPub_ = nh_.advertise<mavros_msgs::AttitudeTarget>("command/bodyrate_command", 1);
2929
referencePosePub_ = nh_.advertise<geometry_msgs::PoseStamped>("reference/pose", 1);
3030
target_pose_pub_ = nh_.advertise<geometry_msgs::PoseStamped>("/mavros/setpoint_position/local", 10);
31+
posehistoryPub_ = nh_.advertise<nav_msgs::Path>("/geometric_controller/path", 10);
3132

3233
arming_client_ = nh_.serviceClient<mavros_msgs::CommandBool>("/mavros/cmd/arming");
3334
set_mode_client_ = nh_.serviceClient<mavros_msgs::SetMode>("/mavros/set_mode");
@@ -50,6 +51,7 @@ geometricCtrl::geometricCtrl(const ros::NodeHandle& nh, const ros::NodeHandle& n
5051
nh_.param<double>("/geometric_controller/Kv_x", Kvel_x_, 1.5);
5152
nh_.param<double>("/geometric_controller/Kv_y", Kvel_y_, 1.5);
5253
nh_.param<double>("/geometric_controller/Kv_z", Kvel_z_, 3.3);
54+
nh_.param<int>("/geometric_controller/posehistory_window", posehistory_window_, 200);
5355

5456
targetPos_ << 0.0, 0.0, 2.0; //Initial Position
5557
targetVel_ << 0.0, 0.0, 0.0;
@@ -59,6 +61,7 @@ geometricCtrl::geometricCtrl(const ros::NodeHandle& nh, const ros::NodeHandle& n
5961
D_ << dx_, dy_, dz_;
6062

6163
tau << tau_x, tau_y, tau_z;
64+
6265
}
6366
geometricCtrl::~geometricCtrl() {
6467
//Destructor
@@ -189,6 +192,8 @@ void geometricCtrl::cmdloopCallback(const ros::TimerEvent& event){
189192
if(!feedthrough_enable_) computeBodyRateCmd(false);
190193
pubReferencePose();
191194
pubRateCommands();
195+
appendPoseHistory();
196+
pubPoseHistory();
192197
break;
193198
case LANDING: {
194199
geometry_msgs::PoseStamped landingmsg;
@@ -257,6 +262,36 @@ void geometricCtrl::pubRateCommands(){
257262
angularVelPub_.publish(angularVelMsg_);
258263
}
259264

265+
void geometricCtrl::pubPoseHistory(){
266+
nav_msgs::Path msg;
267+
msg.header.stamp = ros::Time::now();
268+
msg.header.frame_id = "map";
269+
msg.poses = posehistory_vector_;
270+
posehistoryPub_.publish(msg);
271+
}
272+
273+
void geometricCtrl::appendPoseHistory(){
274+
posehistory_vector_.insert(posehistory_vector_.begin(), vector3d2PoseStampedMsg(mavPos_, mavAtt_));
275+
if(posehistory_vector_.size() > posehistory_window_){
276+
posehistory_vector_.pop_back();
277+
}
278+
}
279+
280+
geometry_msgs::PoseStamped geometricCtrl::vector3d2PoseStampedMsg(Eigen::Vector3d &position, Eigen::Vector4d &orientation){
281+
geometry_msgs::PoseStamped encode_msg;
282+
encode_msg.header.stamp = ros::Time::now();
283+
encode_msg.header.frame_id = "map";
284+
encode_msg.pose.orientation.w = orientation(0);
285+
encode_msg.pose.orientation.x = orientation(1);
286+
encode_msg.pose.orientation.y = orientation(2);
287+
encode_msg.pose.orientation.z = orientation(3);
288+
encode_msg.pose.position.x = position(0);
289+
encode_msg.pose.position.y = position(1);
290+
encode_msg.pose.position.z = position(2);
291+
return encode_msg;
292+
}
293+
294+
260295
void geometricCtrl::computeBodyRateCmd(bool ctrl_mode){
261296
Eigen::Matrix3d R_ref;
262297

@@ -401,4 +436,4 @@ void geometricCtrl::setBodyRateCommand(Eigen::Vector4d bodyrate_command){
401436
void geometricCtrl::setFeedthrough(bool feed_through){
402437
feedthrough_enable_ = feed_through;
403438

404-
}
439+
}

0 commit comments

Comments
 (0)