File tree Expand file tree Collapse file tree 1 file changed +2
-5
lines changed 
joint_state_controller/src Expand file tree Collapse file tree 1 file changed +2
-5
lines changed Original file line number Diff line number Diff line change @@ -66,15 +66,12 @@ const
6666rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn
6767JointStateController::on_configure (const  rclcpp_lifecycle::State & /* previous_state*/ 
6868{
69-   if  (!node_.get ()) {
70-     return  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
71-   }
7269  try  {
73-     joint_state_publisher_ = node_ ->create_publisher <sensor_msgs::msg::JointState>(
70+     joint_state_publisher_ = get_node () ->create_publisher <sensor_msgs::msg::JointState>(
7471      " joint_states" rclcpp::SystemDefaultsQoS ());
7572
7673    dynamic_joint_state_publisher_ =
77-       node_ ->create_publisher <control_msgs::msg::DynamicJointState>(
74+       get_node () ->create_publisher <control_msgs::msg::DynamicJointState>(
7875      " dynamic_joint_states" rclcpp::SystemDefaultsQoS ());
7976  } catch  (...) {
8077    return  rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
 
 
   
 
     
   
   
          
    
    
     
    
      
     
     
    You can’t perform that action at this time.
  
 
    
  
    
      
        
     
       
      
     
   
 
    
    
  
 
  
 
     
    
0 commit comments