4 roslib.load_manifest(
"posedetection_msgs")
 
    5 roslib.load_manifest(
"dynamic_tf_publisher")
 
    6 from posedetection_msgs.msg 
import ObjectDetection
 
    7 from geometry_msgs.msg 
import Transform
 
    8 from geometry_msgs.msg 
import PoseStamped
 
   15         if rospy.get_param(
'~use_simple_tf', 
False):
 
   19             self.
frame_id = rospy.get_param(
"~frame_id", 
"object")
 
   24         if rospy.has_param(
'~checker_board_params/position_x'):
 
   25             position_x = rospy.get_param(
'~checker_board_params/position_x', 0)
 
   26             position_y = rospy.get_param(
'~checker_board_params/position_y', 0)
 
   27             position_z = rospy.get_param(
'~checker_board_params/position_z', 0)
 
   28             orientation_x = rospy.get_param(
'~checker_board_params/orientation_x', 0)
 
   29             orientation_y = rospy.get_param(
'~checker_board_params/orientation_y', 0)
 
   30             orientation_z = rospy.get_param(
'~checker_board_params/orientation_z', 0)
 
   31             orientation_w = rospy.get_param(
'~checker_board_params/orientation_w', 0)
 
   32             rospy.loginfo(
"objectdetection_tf_publisher load the calibration params :")
 
   33             rospy.loginfo(
"    pos : %f %f %f orientation %f %f %f %f", position_x, position_y, position_z, orientation_x, orientation_y, orientation_z, orientation_w)
 
   36                                          orientation_x,orientation_y,orientation_z,orientation_w,
 
   37                                          rospy.get_param(
'~checker_board_params/header_frame'),
 
   41             rospy.loginfo(
"No parameters (~checker_board_params)  was found for object detection")
 
   45             for detected_object 
in msg.objects:
 
   46                 self.
br.sendTransform((detected_object.pose.position.x, detected_object.pose.position.y, detected_object.pose.position.z),
 
   47                                       (detected_object.pose.orientation.x, detected_object.pose.orientation.y, detected_object.pose.orientation.z, detected_object.pose.orientation.w),
 
   54             for detected_object 
in msg.objects:
 
   56                     detected_object.pose.position.x,
 
   57                     detected_object.pose.position.y,
 
   58                     detected_object.pose.position.z,
 
   59                     detected_object.pose.orientation.x,
 
   60                     detected_object.pose.orientation.y,
 
   61                     detected_object.pose.orientation.z,
 
   62                     detected_object.pose.orientation.w,
 
   69         transform.translation.x = pos_x
 
   70         transform.translation.y = pos_y
 
   71         transform.translation.z = pos_z
 
   72         transform.rotation.x = ori_x
 
   73         transform.rotation.y = ori_y
 
   74         transform.rotation.z = ori_z
 
   75         transform.rotation.w = ori_w
 
   77         set_tf_request = SetDynamicTFRequest()
 
   78         set_tf_request.freq = 10
 
   79         set_tf_request.cur_tf.header.stamp = rospy.get_rostime()
 
   80         set_tf_request.cur_tf.header.frame_id = parent_frame_id
 
   81         set_tf_request.cur_tf.child_frame_id = child_frame_id
 
   82         set_tf_request.cur_tf.transform = transform
 
   84         rospy.wait_for_service(
'/set_dynamic_tf')
 
   85         set_dynamic_tf = rospy.ServiceProxy(
'/set_dynamic_tf', SetDynamicTF)
 
   87             res = set_dynamic_tf(set_tf_request)
 
   88         except rospy.ServiceException 
as exc:
 
   89             print((
"Service did not process request: " + str(exc)))
 
   91 if __name__== 
'__main__':
 
   92     rospy.init_node(
'objectdetection_tf_publisher', anonymous=
True)