@@ -522,11 +522,24 @@ URPositionHardwareInterface::on_configure(const rclcpp_lifecycle::State& previou
522522 registerUrclLogHandler (tf_prefix);
523523 try {
524524 rtde_comm_has_been_started_ = false ;
525- ur_driver_ = std::make_unique<urcl::UrDriver>(
526- robot_ip, script_filename, output_recipe_filename, input_recipe_filename,
527- std::bind (&URPositionHardwareInterface::handleRobotProgramState, this , std::placeholders::_1), headless_mode,
528- std::move (tool_comm_setup), (uint32_t )reverse_port, (uint32_t )script_sender_port, servoj_gain,
529- servoj_lookahead_time, non_blocking_read_, reverse_ip, trajectory_port, script_command_port);
525+ urcl::UrDriverConfiguration driver_config;
526+ driver_config.robot_ip = robot_ip;
527+ driver_config.script_file = script_filename;
528+ driver_config.output_recipe_file = output_recipe_filename;
529+ driver_config.input_recipe_file = input_recipe_filename;
530+ driver_config.headless_mode = headless_mode;
531+ driver_config.reverse_port = static_cast <uint32_t >(reverse_port);
532+ driver_config.script_sender_port = static_cast <uint32_t >(script_sender_port);
533+ driver_config.trajectory_port = static_cast <uint32_t >(trajectory_port);
534+ driver_config.script_command_port = static_cast <uint32_t >(script_command_port);
535+ driver_config.reverse_ip = reverse_ip;
536+ driver_config.servoj_gain = static_cast <uint32_t >(servoj_gain);
537+ driver_config.servoj_lookahead_time = servoj_lookahead_time;
538+ driver_config.non_blocking_read = non_blocking_read_;
539+ driver_config.tool_comm_setup = std::move (tool_comm_setup);
540+ driver_config.handle_program_state =
541+ std::bind (&URPositionHardwareInterface::handleRobotProgramState, this , std::placeholders::_1);
542+ ur_driver_ = std::make_unique<urcl::UrDriver>(driver_config);
530543 } catch (urcl::ToolCommNotAvailable& e) {
531544 RCLCPP_FATAL_STREAM (rclcpp::get_logger (" URPositionHardwareInterface" ), " See parameter use_tool_communication" );
532545
0 commit comments