@@ -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}
6366geometricCtrl::~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+
260295void geometricCtrl::computeBodyRateCmd (bool ctrl_mode){
261296 Eigen::Matrix3d R_ref;
262297
@@ -401,4 +436,4 @@ void geometricCtrl::setBodyRateCommand(Eigen::Vector4d bodyrate_command){
401436void geometricCtrl::setFeedthrough (bool feed_through){
402437 feedthrough_enable_ = feed_through;
403438
404- }
439+ }
0 commit comments