@@ -93,7 +93,7 @@ state_interface_configuration() const
9393 conf.names .reserve (2 * joint_names_.size ());
9494 for (const auto & joint_name : joint_names_) {
9595 conf.names .push_back (joint_name + " /" + hardware_interface::HW_IF_POSITION);
96- conf.names .push_back (joint_name + " /" + hardware_interface::HW_IF_VELOCITY);
96+ // conf.names.push_back(joint_name + "/" + hardware_interface::HW_IF_VELOCITY);
9797 }
9898 return conf;
9999}
@@ -142,10 +142,14 @@ JointTrajectoryController::update()
142142 // current state update
143143 for (auto index = 0ul ; index < joint_num; ++index) {
144144 state_current.positions [index] = joint_position_state_interface_[index].get ().get_value ();
145- state_current.velocities [index] = joint_velocity_state_interface_[index].get ().get_value ();
145+ // state_current.velocities[index] = joint_velocity_state_interface_[index].get().get_value();
146+ state_current.velocities [index] = 0.0 ;
146147 state_current.accelerations [index] = 0.0 ;
147148 }
148149 state_current.time_from_start .set__sec (0 );
150+ // Make velocity and accel empty -- those will not be considered during interpolation
151+ state_current.velocities .clear ();
152+ state_current.accelerations .clear ();
149153
150154 // currently carrying out a trajectory
151155 if (traj_point_active_ptr_ && (*traj_point_active_ptr_)->has_trajectory_msg () == false ) {
@@ -395,16 +399,16 @@ JointTrajectoryController::on_activate(const rclcpp_lifecycle::State &)
395399 joint_names_.size (), joint_position_state_interface_.size ());
396400 return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
397401 }
398- if (!get_ordered_interfaces (
399- state_interfaces_, joint_names_, hardware_interface::HW_IF_VELOCITY,
400- joint_velocity_state_interface_))
401- {
402- RCLCPP_ERROR (
403- node_->get_logger (),
404- " Expected %u velocity state interfaces, got %u" ,
405- joint_names_.size (), joint_velocity_state_interface_.size ());
406- return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
407- }
402+ // if (!get_ordered_interfaces(
403+ // state_interfaces_, joint_names_, hardware_interface::HW_IF_VELOCITY,
404+ // joint_velocity_state_interface_))
405+ // {
406+ // RCLCPP_ERROR(
407+ // node_->get_logger(),
408+ // "Expected %u velocity state interfaces, got %u",
409+ // joint_names_.size(), joint_velocity_state_interface_.size());
410+ // return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
411+ // }
408412
409413 // Store 'home' pose
410414 traj_msg_home_ptr_ = std::make_shared<trajectory_msgs::msg::JointTrajectory>();
@@ -436,7 +440,7 @@ JointTrajectoryController::on_deactivate(const rclcpp_lifecycle::State &)
436440{
437441 joint_position_command_interface_.clear ();
438442 joint_position_state_interface_.clear ();
439- joint_velocity_state_interface_.clear ();
443+ // joint_velocity_state_interface_.clear();
440444 release_interfaces ();
441445
442446 subscriber_is_active_ = false ;
0 commit comments