ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to change pitch of camera in Gazebo?

asked 2018-05-08 03:36:24 -0500

KrizChong gravatar image

updated 2018-05-08 03:37:20 -0500

I am working on a TB3 simulation in Gazebo as https://www.youtube.com/watch?v=RgOvX...

I want to change the pitch of the camera on TB3 to look lower, so that TB3 still can see the ball even it is very close.

But which file and parameter should I change? .urdf.xacro? .gazebo.xacro? model.config? model.sdf?

There are many files with similar setting that confusing me...

Please advise, thank you.

edit retag flag offensive close merge delete

Comments

can you share referred GitHub link for better understanding?

simbha gravatar image simbha  ( 2018-05-08 03:59:17 -0500 )edit

The robot description are in https://github.com/ROBOTIS-GIT/turtle... . The simulation models are from https://github.com/ROBOTIS-GIT/turtle... . The model I use is waffle_pi

KrizChong gravatar image KrizChong  ( 2018-05-08 04:01:15 -0500 )edit

I did edit turtlebot3/turtlebot3_description/urdf/turtlebot3_waffle_pi.gazebo.xacro, when I change the FOV of Pi camera, it show the view of camera is changed, but when I change the pose of Pi camera, nothing change on the view of camera...

KrizChong gravatar image KrizChong  ( 2018-05-08 04:05:53 -0500 )edit

In the same file mention above, you will find in the camera sensor pose as <pose>0.003 0.011 0.008 0 0 0</pose>. This pose actually has 6 elements x,y,z,r,p,y. This r,p,y stand for roll pitch and yaw. by changing these parameters you can change the roll pitch and yaw of joint.

simbha gravatar image simbha  ( 2018-05-08 04:28:31 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
2

answered 2018-05-08 08:14:46 -0500

Here is some of my urdf.xacro file that impliments a camera at a specified camera_pitch. Note line 11: <origin xyz="0 0 ${1+base_height}" rpy="0 ${-cam_pitch} 0"/>

<!-- Vision Camera -->
    <link name="camera_link">
        <visual>
            <origin xyz="0 0 0" rpy="0 0 0" />
            <geometry>
                <box size="${camera_size} ${camera_size} ${camera_size}" />
            </geometry>
        </visual>
    </link>
    <joint name="camera_joint" type="fixed">
      <origin xyz="0 0 ${1+base_height}" rpy="0 ${-cam_pitch} 0" />
      <parent link="base_link"/>
      <child link="camera_link" />
    </joint>
    <gazebo reference="camera_link">
      <sensor type="camera" name="camera">
        <update_rate>30.0</update_rate>
        <camera name="head">
          <horizontal_fov>1.3962634</horizontal_fov>
          <image>
            <width>752</width>
            <height>480</height>
            <format>L8</format>
          </image>
          <clip>
            <near>0.02</near>
            <far>300</far>
          </clip>
          <!--noise>
            <type>gaussian</type>
            < Noise is sampled independently per pixel on each frame.
                 That pixel's noise value is added to each of its color
                 channels, which at that point lie in the range [0,1]. >
            <mean>0.0</mean>
            <stddev>0.007</stddev>
          </noise-->
        </camera>
        <plugin name="camera_controller" filename="libgazebo_ros_camera.so">
          <alwaysOn>true</alwaysOn>
          <updateRate>0.0</updateRate>
          <cameraName>camera</cameraName>
          <imageTopicName>image_raw</imageTopicName>
          <cameraInfoTopicName>camera_info</cameraInfoTopicName>
          <frameName>camera_link</frameName>
          <hackBaseline>0.07</hackBaseline>
          <distortionK1>0.0</distortionK1>
          <distortionK2>0.0</distortionK2>
          <distortionK3>0.0</distortionK3>
          <distortionT1>0.0</distortionT1>
          <distortionT2>0.0</distortionT2>
        </plugin>
      </sensor>
    </gazebo>
edit flag offensive delete link more

Comments

1

Sorry for late reply, I tried it just now, it works! thank you very much!!!

KrizChong gravatar image KrizChong  ( 2018-05-09 07:41:39 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2018-05-08 03:36:24 -0500

Seen: 2,805 times

Last updated: May 08 '18