46 ROS_FATAL_STREAM_NAMED(
"qb_hand_gazebo_plugin",
"Unable to load qb SoftHand Gazebo plugin: a ROS node for Gazebo has not been initialized yet.");
50 #if GAZEBO_MAJOR_VERSION >= 8
60 ROS_WARN_STREAM_NAMED(
"qb_hand_gazebo_plugin",
"Desired controller update period (" <<
control_period_ <<
" s) is faster than the Gazebo simulation period (" << gazebo_period <<
" s).");
66 ROS_ERROR_STREAM_NAMED(
"qb_hand_gazebo_plugin",
"Error while parsing transmissions in the URDF for the qb SoftHand Gazebo plugin.");
75 robot_hw_sim_ = std::make_shared<gazebo_ros_control::CombinedRobotHWSim>();
77 ROS_FATAL_STREAM_NAMED(
"qb_hand_gazebo_plugin",
"Error while initializing the robot simulation interface");
83 ROS_INFO_NAMED(
"qb_hand_gazebo_plugin",
"qb SoftHand Gazebo plugin successfully loaded.");
87 ros::Time sim_time_ros(info.simTime.sec, info.simTime.nsec);
100 std::string urdf_string;
102 while (urdf_string.empty()) {
103 std::string search_param_name;
105 ROS_INFO_STREAM_ONCE_NAMED(
"qb_hand_gazebo_plugin",
"qb SoftHand Gazebo plugin is waiting for model URDF in parameter [" << search_param_name <<
"] on the ROS param server.");