Skip to content

Commit cd459c7

Browse files
authored
apply to master API (ros-navigation#13)
Signed-off-by: Karsten Knese <[email protected]>
1 parent 9001021 commit cd459c7

File tree

1 file changed

+4
-3
lines changed

1 file changed

+4
-3
lines changed

ros_controllers/src/trajectory.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -53,7 +53,8 @@ Trajectory::update(std::shared_ptr<trajectory_msgs::msg::JointTrajectory> joint_
5353
TrajectoryPointConstIter
5454
Trajectory::sample(const rclcpp::Time & sample_time)
5555
{
56-
THROW_ON_NULLPTR(trajectory_msg_)
56+
// TODO(karsten1987): Enable this for eloquent when `rclcpp::is_pointer` is used
57+
// THROW_ON_NULLPTR(trajectory_msg_)
5758

5859
// skip if current time hasn't reached traj time of the first msg yet
5960
if (time_less_than(sample_time, trajectory_start_time_)) {
@@ -74,15 +75,15 @@ Trajectory::sample(const rclcpp::Time & sample_time)
7475
TrajectoryPointConstIter
7576
Trajectory::begin() const
7677
{
77-
THROW_ON_NULLPTR(trajectory_msg_)
78+
// THROW_ON_NULLPTR(trajectory_msg_)
7879

7980
return trajectory_msg_->points.begin();
8081
}
8182

8283
TrajectoryPointConstIter
8384
Trajectory::end() const
8485
{
85-
THROW_ON_NULLPTR(trajectory_msg_)
86+
// THROW_ON_NULLPTR(trajectory_msg_)
8687

8788
return trajectory_msg_->points.end();
8889
}

0 commit comments

Comments
 (0)