@@ -265,6 +265,14 @@ controller_interface::CallbackReturn AdmittanceController::on_configure(
265
265
input_joint_command_subscriber_ =
266
266
get_node ()->create_subscription <trajectory_msgs::msg::JointTrajectoryPoint>(
267
267
" ~/joint_references" , rclcpp::SystemDefaultsQoS (), joint_command_callback);
268
+
269
+ auto goal_pose_callback =
270
+ [this ](const std::shared_ptr<geometry_msgs::msg::Pose> msg)
271
+ { input_goal_pose_.writeFromNonRT (msg); };
272
+ input_goal_pose_subscriber_ =
273
+ get_node ()->create_subscription <geometry_msgs::msg::Pose>(
274
+ " ~/goal_pose" , rclcpp::SystemDefaultsQoS (), goal_pose_callback);
275
+
268
276
s_publisher_ = get_node ()->create_publisher <control_msgs::msg::AdmittanceControllerState>(
269
277
" ~/status" , rclcpp::SystemDefaultsQoS ());
270
278
state_publisher_ =
@@ -347,6 +355,14 @@ controller_interface::CallbackReturn AdmittanceController::on_activate(
347
355
}
348
356
}
349
357
358
+ goal_pose_msg_ = std::make_shared<geometry_msgs::msg::Pose>(
359
+ admittance_->initialize_goal_pose (joint_state_)
360
+ );
361
+ if (!goal_pose_msg_){
362
+ RCLCPP_ERROR (get_node ()->get_logger (), " Failed to initialize goal_pose from current joint positions.\n " );
363
+ return controller_interface::CallbackReturn::ERROR;
364
+ }
365
+
350
366
// Use current joint_state as a default reference
351
367
last_reference_ = joint_state_;
352
368
last_commanded_ = joint_state_;
@@ -380,6 +396,14 @@ controller_interface::return_type AdmittanceController::update_reference_from_su
380
396
}
381
397
}
382
398
399
+ // after initializing goal_pose_msg_, update it from subscribers only
400
+ // if another message exists
401
+ if (*input_goal_pose_.readFromRT ())
402
+ {
403
+ goal_pose_msg_ = *input_goal_pose_.readFromRT ();
404
+ }
405
+
406
+
383
407
return controller_interface::return_type::OK;
384
408
}
385
409
@@ -404,17 +428,8 @@ controller_interface::return_type AdmittanceController::update_and_write_command
404
428
// get all controller inputs
405
429
read_state_from_hardware (joint_state_, ft_values_);
406
430
407
- auto goal_pose = geometry_msgs::msg::Pose ();
408
- /* world-tool0*/
409
- goal_pose.position .x = 1.53 ;
410
- goal_pose.position .y = 0.9 ;
411
- goal_pose.position .z = 1.5 ;
412
- goal_pose.orientation .w = 0.0 ;
413
- goal_pose.orientation .x = 0.707 ;
414
- goal_pose.orientation .y = 0.0 ;
415
- goal_pose.orientation .z = 0.707 ;
416
431
// apply admittance control to reference to determine desired state
417
- admittance_->update (joint_state_, ft_values_, goal_pose , reference_, period, reference_admittance_);
432
+ admittance_->update (joint_state_, ft_values_, *goal_pose_msg_ , reference_, period, reference_admittance_);
418
433
419
434
// write calculated values to joint interfaces
420
435
write_state_to_hardware (reference_admittance_);
0 commit comments