@@ -939,22 +939,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
939939 }
940940 }
941941
942- // Store 'home' pose
943- traj_msg_home_ptr_ = std::make_shared<trajectory_msgs::msg::JointTrajectory>();
944- traj_msg_home_ptr_->header .stamp .sec = 0 ;
945- traj_msg_home_ptr_->header .stamp .nanosec = 0 ;
946- traj_msg_home_ptr_->points .resize (1 );
947- traj_msg_home_ptr_->points [0 ].time_from_start .sec = 0 ;
948- traj_msg_home_ptr_->points [0 ].time_from_start .nanosec = 50000000 ;
949- traj_msg_home_ptr_->points [0 ].positions .resize (joint_state_interface_[0 ].size ());
950- for (size_t index = 0 ; index < joint_state_interface_[0 ].size (); ++index)
951- {
952- traj_msg_home_ptr_->points [0 ].positions [index] =
953- joint_state_interface_[0 ][index].get ().get_value ();
954- }
955-
956942 traj_external_point_ptr_ = std::make_shared<Trajectory>();
957- traj_home_point_ptr_ = std::make_shared<Trajectory>();
958943 traj_msg_external_point_ptr_.writeFromNonRT (
959944 std::shared_ptr<trajectory_msgs::msg::JointTrajectory>());
960945
@@ -1045,22 +1030,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
10451030 subscriber_is_active_ = false ;
10461031
10471032 traj_external_point_ptr_.reset ();
1048- traj_home_point_ptr_.reset ();
1049- traj_msg_home_ptr_.reset ();
10501033
10511034 return CallbackReturn::SUCCESS;
10521035}
10531036
10541037controller_interface::CallbackReturn JointTrajectoryController::on_cleanup (
10551038 const rclcpp_lifecycle::State &)
10561039{
1057- // go home
1058- if (traj_home_point_ptr_ != nullptr )
1059- {
1060- traj_home_point_ptr_->update (traj_msg_home_ptr_);
1061- traj_external_point_ptr_ = traj_home_point_ptr_;
1062- }
1063-
10641040 return CallbackReturn::SUCCESS;
10651041}
10661042
@@ -1087,11 +1063,7 @@ bool JointTrajectoryController::reset()
10871063 }
10881064 }
10891065
1090- // iterator has no default value
1091- // prev_traj_point_ptr_;
10921066 traj_external_point_ptr_.reset ();
1093- traj_home_point_ptr_.reset ();
1094- traj_msg_home_ptr_.reset ();
10951067
10961068 return true ;
10971069}
0 commit comments