Skip to content

Commit 41610fd

Browse files
[JTC] Remove unused home pose (#845)
1 parent 25f2a14 commit 41610fd

File tree

2 files changed

+0
-30
lines changed

2 files changed

+0
-30
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 0 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -184,8 +184,6 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
184184
rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;
185185

186186
std::shared_ptr<Trajectory> traj_external_point_ptr_ = nullptr;
187-
std::shared_ptr<Trajectory> traj_home_point_ptr_ = nullptr;
188-
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> traj_msg_home_ptr_ = nullptr;
189187
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectory>>
190188
traj_msg_external_point_ptr_;
191189

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 0 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -921,22 +921,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
921921
}
922922
}
923923

924-
// Store 'home' pose
925-
traj_msg_home_ptr_ = std::make_shared<trajectory_msgs::msg::JointTrajectory>();
926-
traj_msg_home_ptr_->header.stamp.sec = 0;
927-
traj_msg_home_ptr_->header.stamp.nanosec = 0;
928-
traj_msg_home_ptr_->points.resize(1);
929-
traj_msg_home_ptr_->points[0].time_from_start.sec = 0;
930-
traj_msg_home_ptr_->points[0].time_from_start.nanosec = 50000000;
931-
traj_msg_home_ptr_->points[0].positions.resize(joint_state_interface_[0].size());
932-
for (size_t index = 0; index < joint_state_interface_[0].size(); ++index)
933-
{
934-
traj_msg_home_ptr_->points[0].positions[index] =
935-
joint_state_interface_[0][index].get().get_value();
936-
}
937-
938924
traj_external_point_ptr_ = std::make_shared<Trajectory>();
939-
traj_home_point_ptr_ = std::make_shared<Trajectory>();
940925
traj_msg_external_point_ptr_.writeFromNonRT(
941926
std::shared_ptr<trajectory_msgs::msg::JointTrajectory>());
942927

@@ -1028,22 +1013,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
10281013
subscriber_is_active_ = false;
10291014

10301015
traj_external_point_ptr_.reset();
1031-
traj_home_point_ptr_.reset();
1032-
traj_msg_home_ptr_.reset();
10331016

10341017
return CallbackReturn::SUCCESS;
10351018
}
10361019

10371020
controller_interface::CallbackReturn JointTrajectoryController::on_cleanup(
10381021
const rclcpp_lifecycle::State &)
10391022
{
1040-
// go home
1041-
if (traj_home_point_ptr_ != nullptr)
1042-
{
1043-
traj_home_point_ptr_->update(traj_msg_home_ptr_);
1044-
traj_external_point_ptr_ = traj_home_point_ptr_;
1045-
}
1046-
10471023
return CallbackReturn::SUCCESS;
10481024
}
10491025

@@ -1070,11 +1046,7 @@ bool JointTrajectoryController::reset()
10701046
}
10711047
}
10721048

1073-
// iterator has no default value
1074-
// prev_traj_point_ptr_;
10751049
traj_external_point_ptr_.reset();
1076-
traj_home_point_ptr_.reset();
1077-
traj_msg_home_ptr_.reset();
10781050

10791051
return true;
10801052
}

0 commit comments

Comments
 (0)