## repository: https://code.ros.org/svn/ros-pkg <> <> {{attachment:image_rotate.jpg}} <> == Example Use == To produce a version of the forearm camera view that always points up: {{{ rosrun image_rotate image_rotate image:=l_forearm_cam/image_color \ rotated/image:=l_forearm_cam/image_color_rotated __name:=image_rotater }}} You can then view it with `image_view`. {{{ rosrun image_view image_view image:=l_forearm_cam/image_color_rotated }}} It is easy to adjust the settings using `rqt_reconfigure`. {{{ rosrun rqt_reconfigure rqt_reconfigure image_rotater }}} == ROS API == {{{ #!clearsilver CS/NodeAPI node.0 { name=image_rotate desc=`image_rotate` is a node to rotate an image for visualization. The node takes a source vector and a target vector, and projects them onto the camera image. It then rotates the image by the angle neded to align the projection of the source vector with the projection of the target vector. The source and target vectors are specified in arbitrary TF frames allowing the rotation angle to vary dynamically as frames move relative to one another. With the default settings, the image will be rotated so that the top of the image matches the up direction the `base_link`. sub{ 0.name= image 0.type= sensor_msgs/Image 0.desc= Image to be rotated (the accompanying camera_info may also be subscribed to). } pub{ 1.name= rotated/image 1.type= sensor_msgs/Image 1.desc= Rotated image } # Autogenerated param section. Do not hand edit. param { group.0 { name=Dynamically Reconfigurable Parameters desc=See the [[dynamic_reconfigure]] package for details on dynamically reconfigurable parameters. 0.name= ~target_frame_id 0.default= base_link 0.type= str 0.desc=Frame in which the target vector is specified. Empty means the input frame. 1.name= ~target_x 1.default= 0.0 1.type= double 1.desc=X coordinate of the target vector Range: -10.0 to 10.0 2.name= ~target_y 2.default= 0.0 2.type= double 2.desc=Y coordinate of the target vector Range: -10.0 to 10.0 3.name= ~target_z 3.default= 1.0 3.type= double 3.desc=Z coordinate of the target vector Range: -10.0 to 10.0 4.name= ~source_frame_id 4.default= 4.type= str 4.desc=Frame in which the source vector is specified. Empty means the input frame. 5.name= ~source_x 5.default= 0.0 5.type= double 5.desc=X coordinate of the direction the target should be aligned with. Range: -10.0 to 10.0 6.name= ~source_y 6.default= -1.0 6.type= double 6.desc=Y coordinate of the direction the target should be aligned with. Range: -10.0 to 10.0 7.name= ~source_z 7.default= 0.0 7.type= double 7.desc=Z coordinate of the direction the target should be aligned with. Range: -10.0 to 10.0 8.name= ~output_frame_id 8.default= 8.type= str 8.desc=Frame to publish for the image's new orientation. Empty means add '_rotated' suffix to the image frame. 9.name= ~input_frame_id 9.default= 9.type= str 9.desc=Frame to use for the original camera image. Empty means that the frame in the image or camera_info should be used depending on use_camera_info. 10.name= ~use_camera_info 10.default= True 10.type= bool 10.desc=Indicates that the camera_info topic should be subscribed to to get the default input_frame_id. Otherwise the frame from the image message will be used. 11.name= ~max_angular_rate 11.default= 10.0 11.type= double 11.desc=Limits the rate at which the image can rotate (rad/s). Zero means no limit. Range: 0.0 to 100.0 12.name= ~output_image_size 12.default= 2.0 12.type= double 12.desc=Size of the output image as a function of the input image size. Can be varied continuously between the following special settings: 0 ensures no black ever appears, 1 is small image dimension, 2 is large image dimension, 3 is image diagonal. Range: 0.0 to 3.0 } } # End of autogenerated section. You may edit below. }}} ## AUTOGENERATED DON'T DELETE ## CategoryPackage