Husarnet Tutorial , smartphone view orientation

Hi Husarion Team,

Reference:
https://husarion.com/tutorials/husarnet/following-object-using-your-smartphone/

My 3 nodes are working fine.
My robot reacts to the object-position on the viewing panel of FIND-OBJECT shell

The view of the surrounding on the FIND-OBJECT panel, while the smartphone is in the portrait-stand, is 90 degree rotated to the right.

Question is, how can I correct this mismatch?

Thanks and regards,
Fred

Hello Fred,

I think you could use image_rotate package to position your camera view correctly.
You can find it here:
http://wiki.ros.org/image_rotate

Regards,
Łukasz

Hello Lukasz,

Thanks the link you have provided me.

My problem is related to the “following-object-using_your_smartphone” sample

I have tried to use it, but I am not able to achieve something with the view on the Find-Object panel.

How do I have to link this ‘image_rotate’ -method to the image coming from the camera of the smartphone,
before it is grabbed and used by the “object_follower” program and executed by “follower_main”
Can you help me on this?
Thanks and regards,
Fred

Hello Fred,

I prepared a launch file that uses image_rotate node, this is a complete example, provided that you have phone and laptop connected in husarnet.

<launch>
    <node pkg="image_rotate" type="image_rotate" name="image_rotater">
        <remap from="image" to="/localimg"/>
        <param name="use_camera_info" value="true"/>
        <param name="target_x" value="-1"/>
    </node>
    <node pkg="find_object_2d" type="find_object_2d" name="find_object_2d" output="screen">
        <remap from="image" to="/rotated/image"/>
        <param name="gui" value="true"/>
    </node>
    <node pkg="tf" type="static_transform_publisher" name="tf4" args="0 0 0 0 0 0 base_link front 100" />
    <node pkg="image_transport" type="republish" name="republish" output="screen" args="compressed in:=/myPhone/camera0/image out:=/localimg">
    </node>
</launch>

Moreover image rotate needs camera info to work properly, it can be published with a python script:

#!/usr/bin/env python
import rospy
from sensor_msgs.msg import CameraInfo
from sensor_msgs.msg import Image
import std_msgs.msg

camera_info_msg = 0

def callback(data):
    global camera_info_msg
    camera_info_msg.header=data.header
    camera_info_msg.header.frame_id="front"
    publisher.publish(camera_info_msg)

if __name__ == "__main__":
    camera_info_msg = CameraInfo()
    camera_info_msg.width = 640
    camera_info_msg.height = 480
    camera_info_msg.K = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    camera_info_msg.D = []
    camera_info_msg.R = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    camera_info_msg.P = [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
    camera_info_msg.distortion_model = ''
    # Initialize publisher node
    rospy.init_node("camera_info_publisher", anonymous=True)
    publisher = rospy.Publisher("camera_info", CameraInfo, queue_size=10)

    rospy.Subscriber("localimg", Image, callback)
    rospy.spin()

Regards,
Łukasz

Hello Lukasz,

Your program does its jobs! Excellent.

I have only changed the line

into to get the correct orientation.

I am happy with the view now and it does not look silly anymore!

Thank you very much for the great help.
Best regards,
Fred

lines are not showing up in my previous message

I have changed the value of the parameter “target_x” from -1 into 1