Skip to content

Commit

Permalink
[JTC] Remove unused home pose (backport #845)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Nov 19, 2023
1 parent 1d3f1e2 commit ca4f72e
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 30 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -183,8 +183,6 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
rclcpp::Service<control_msgs::srv::QueryTrajectoryState>::SharedPtr query_state_srv_;

std::shared_ptr<Trajectory> traj_external_point_ptr_ = nullptr;
std::shared_ptr<Trajectory> traj_home_point_ptr_ = nullptr;
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> traj_msg_home_ptr_ = nullptr;
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectory>>
traj_msg_external_point_ptr_;

Expand Down
28 changes: 0 additions & 28 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -977,22 +977,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
}
}

// Store 'home' pose
traj_msg_home_ptr_ = std::make_shared<trajectory_msgs::msg::JointTrajectory>();
traj_msg_home_ptr_->header.stamp.sec = 0;
traj_msg_home_ptr_->header.stamp.nanosec = 0;
traj_msg_home_ptr_->points.resize(1);
traj_msg_home_ptr_->points[0].time_from_start.sec = 0;
traj_msg_home_ptr_->points[0].time_from_start.nanosec = 50000000;
traj_msg_home_ptr_->points[0].positions.resize(joint_state_interface_[0].size());
for (size_t index = 0; index < joint_state_interface_[0].size(); ++index)
{
traj_msg_home_ptr_->points[0].positions[index] =
joint_state_interface_[0][index].get().get_value();
}

traj_external_point_ptr_ = std::make_shared<Trajectory>();
traj_home_point_ptr_ = std::make_shared<Trajectory>();
traj_msg_external_point_ptr_.writeFromNonRT(
std::shared_ptr<trajectory_msgs::msg::JointTrajectory>());

Expand Down Expand Up @@ -1085,22 +1070,13 @@ controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
subscriber_is_active_ = false;

traj_external_point_ptr_.reset();
traj_home_point_ptr_.reset();
traj_msg_home_ptr_.reset();

return CallbackReturn::SUCCESS;
}

controller_interface::CallbackReturn JointTrajectoryController::on_cleanup(
const rclcpp_lifecycle::State &)
{
// go home
if (traj_home_point_ptr_ != nullptr)
{
traj_home_point_ptr_->update(traj_msg_home_ptr_);
traj_external_point_ptr_ = traj_home_point_ptr_;
}

return CallbackReturn::SUCCESS;
}

Expand All @@ -1127,11 +1103,7 @@ bool JointTrajectoryController::reset()
}
}

// iterator has no default value
// prev_traj_point_ptr_;
traj_external_point_ptr_.reset();
traj_home_point_ptr_.reset();
traj_msg_home_ptr_.reset();

return true;
}
Expand Down

0 comments on commit ca4f72e

Please sign in to comment.