How can I attach different models on a new model. I am unable to attach a camera model to my quadcopter model
I am working on adding a camera model to my Iris Quadcopter. It has Optical Flow camera and Lidar. When I add a new camera, the camera gets left out and it will not stay with my quadcopter.
here is my different model:
Iris:
<sdf version='1.6'>
<model name='iris'>
<link name='base_link'>
<pose frame=''>0 0 0 0 -0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>1.5</mass>
<inertia>
<ixx>0.0347563</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.0458929</iyy>
<iyz>0</iyz>
<izz>0.0977</izz>
</inertia>
</inertial>
<collision name='base_link_inertia_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<box>
<size>0.47 0.47 0.11</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<min_depth>0.001</min_depth>
<max_vel>0</max_vel>
</ode>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='base_link_inertia_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://rotors_description/meshes/iris.stl</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<link name='/imu_link'>
<pose frame=''>0 0 0 0 -0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.015</mass>
<inertia>
<ixx>1e-05</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>1e-05</iyy>
<iyz>0</iyz>
<izz>1e-05</izz>
</inertia>
</inertial>
</link>
<joint name='/imu_joint' type='revolute'>
<child>/imu_link</child>
<parent>base_link</parent>
<axis>
<xyz>1 0 0</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
<effort>0</effort>
<velocity>0</velocity>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_0'>
<pose frame=''>0.13 -0.22 0.023 0 -0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000273104</iyy>
<iyz>0</iyz>
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_0_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.128</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_0_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://rotors_description/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Blue</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<joint name='rotor_0_joint' type='revolute'>
<child>rotor_0</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_1'>
<pose frame=''>-0.13 0.2 0.023 0 -0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000273104</iyy>
<iyz>0</iyz>
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_1_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.128</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_1_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://rotors_description/meshes/iris_prop_ccw.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<joint name='rotor_1_joint' type='revolute'>
<child>rotor_1</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_2'>
<pose frame=''>0.13 0.22 0.023 0 -0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000273104</iyy>
<iyz>0</iyz>
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_2_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.128</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_2_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://rotors_description/meshes/iris_prop_cw.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/Blue</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<joint name='rotor_2_joint' type='revolute'>
<child>rotor_2</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<link name='rotor_3'>
<pose frame=''>-0.13 -0.2 0.023 0 -0 0</pose>
<inertial>
<pose frame=''>0 0 0 0 -0 0</pose>
<mass>0.005</mass>
<inertia>
<ixx>9.75e-07</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.000273104</iyy>
<iyz>0</iyz>
<izz>0.000274004</izz>
</inertia>
</inertial>
<collision name='rotor_3_collision'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<length>0.005</length>
<radius>0.128</radius>
</cylinder>
</geometry>
<surface>
<contact>
<ode/>
</contact>
<friction>
<ode/>
</friction>
</surface>
</collision>
<visual name='rotor_3_visual'>
<pose frame=''>0 0 0 0 -0 0</pose>
<geometry>
<mesh>
<scale>1 1 1</scale>
<uri>model://rotors_description/meshes/iris_prop_cw.dae</uri>
</mesh>
</geometry>
<material>
<script>
<name>Gazebo/DarkGrey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
</material>
</visual>
<gravity>1</gravity>
<velocity_decay/>
</link>
<joint name='rotor_3_joint' type='revolute'>
<child>rotor_3</child>
<parent>base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e+16</lower>
<upper>1e+16</upper>
</limit>
<dynamics>
<spring_reference>0</spring_reference>
<spring_stiffness>0</spring_stiffness>
</dynamics>
<use_parent_model_frame>1</use_parent_model_frame>
</axis>
</joint>
<plugin name='rosbag' filename='librotors_gazebo_multirotor_base_plugin.so'>
<robotNamespace/>
<linkName>base_link</linkName>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_right_motor_model' filename='librotors_gazebo_motor_model.so'>
<robotNamespace/>
<jointName>rotor_0_joint</jointName>
<linkName>rotor_0</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1100</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>0</motorNumber>
<rotorDragCoefficient>0.000806428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/0</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_left_motor_model' filename='librotors_gazebo_motor_model.so'>
<robotNamespace/>
<jointName>rotor_1_joint</jointName>
<linkName>rotor_1</linkName>
<turningDirection>ccw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1100</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>1</motorNumber>
<rotorDragCoefficient>0.000806428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/1</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='front_left_motor_model' filename='librotors_gazebo_motor_model.so'>
<robotNamespace/>
<jointName>rotor_2_joint</jointName>
<linkName>rotor_2</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1100</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>2</motorNumber>
<rotorDragCoefficient>0.000806428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/2</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='back_right_motor_model' filename='librotors_gazebo_motor_model.so'>
<robotNamespace/>
<jointName>rotor_3_joint</jointName>
<linkName>rotor_3</linkName>
<turningDirection>cw</turningDirection>
<timeConstantUp>0.0125</timeConstantUp>
<timeConstantDown>0.025</timeConstantDown>
<maxRotVelocity>1100</maxRotVelocity>
<motorConstant>8.54858e-06</motorConstant>
<momentConstant>0.06</momentConstant>
<commandSubTopic>/gazebo/command/motor_speed</commandSubTopic>
<motorNumber>3</motorNumber>
<rotorDragCoefficient>0.000806428</rotorDragCoefficient>
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
<motorSpeedPubTopic>/motor_speed/3</motorSpeedPubTopic>
<rotorVelocitySlowdownSim>10</rotorVelocitySlowdownSim>
</plugin>
<plugin name='mavlink_interface' filename='librotors_gazebo_mavlink_interface.so'>
<robotNamespace/>
<imuSubTopic>/imu</imuSubTopic>
<mavlink_addr>INADDR_ANY</mavlink_addr>
<mavlink_udp_port>14560</mavlink_udp_port>
<motorSpeedCommandPubTopic>/gazebo/command/motor_speed</motorSpeedCommandPubTopic>
<control_channels>
<channel name='rotor1'>
<input_index>0</input_index>
<input_offset>0</input_offset>
<input_scaling>1000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor2'>
<input_index>1</input_index>
<input_offset>0</input_offset>
<input_scaling>1000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor3'>
<input_index>2</input_index>
<input_offset>0</input_offset>
<input_scaling>1000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor4'>
<input_index>3</input_index>
<input_offset>0</input_offset>
<input_scaling>1000</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>100</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
</channel>
<channel name='rotor5'>
<input_index>4</input_index>
<input_offset>1</input_offset>
<input_scaling>324.6</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>velocity</joint_control_type>
<joint_control_pid>
<p>0.1</p>
<i>0</i>
<d>0</d>
<iMax>0.0</iMax>
<iMin>0.0</iMin>
<cmdMax>2</cmdMax>
<cmdMin>-2</cmdMin>
</joint_control_pid>
<joint_name>zephyr_delta_wing::propeller_joint</joint_name>
</channel>
<channel name='rotor6'>
<input_index>5</input_index>
<input_offset>0</input_offset>
<input_scaling>0.524</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position</joint_control_type>
<joint_name>zephyr_delta_wing::flap_left_joint</joint_name>
<joint_control_pid>
<p>10.0</p>
<i>0</i>
<d>0</d>
<iMax>0</iMax>
<iMin>0</iMin>
<cmdMax>20</cmdMax>
<cmdMin>-20</cmdMin>
</joint_control_pid>
</channel>
<channel name='rotor7'>
<input_index>6</input_index>
<input_offset>0</input_offset>
<input_scaling>0.524</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position</joint_control_type>
<joint_name>zephyr_delta_wing::flap_right_joint</joint_name>
<joint_control_pid>
<p>10.0</p>
<i>0</i>
<d>0</d>
<iMax>0</iMax>
<iMin>0</iMin>
<cmdMax>20</cmdMax>
<cmdMin>-20</cmdMin>
</joint_control_pid>
</channel>
<channel name='rotor8'>
<input_index>7</input_index>
<input_offset>0</input_offset>
<input_scaling>0.524</input_scaling>
<zero_position_disarmed>0</zero_position_disarmed>
<zero_position_armed>0</zero_position_armed>
<joint_control_type>position</joint_control_type>
</channel>
</control_channels>
</plugin>
<static>0</static>
<plugin name='rotors_gazebo_imu_plugin' filename='librotors_gazebo_imu_plugin.so'>
<robotNamespace/>
<linkName>/imu_link</linkName>
<imuTopic>/imu</imuTopic>
<gyroscopeNoiseDensity>0.0003394</gyroscopeNoiseDensity>
<gyroscopeRandomWalk>3.8785e-05</gyroscopeRandomWalk>
<gyroscopeBiasCorrelationTime>1000.0</gyroscopeBiasCorrelationTime>
<gyroscopeTurnOnBiasSigma>0.0087</gyroscopeTurnOnBiasSigma>
<accelerometerNoiseDensity>0.004</accelerometerNoiseDensity>
<accelerometerRandomWalk>0.006</accelerometerRandomWalk>
<accelerometerBiasCorrelationTime>300.0</accelerometerBiasCorrelationTime>
<accelerometerTurnOnBiasSigma>0.196</accelerometerTurnOnBiasSigma>
</plugin>
</model>
</sdf>
flow_cam
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="camera">
<link name="link">
<inertial>
<pose>0.01 0.025 0.025 0 -0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>4.15e-6</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.407e-6</iyy>
<iyz>0</iyz>
<izz>2.407e-6</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<box>
<size>0.02 0.05 0.05</size>
</box>
</geometry>
</visual>
<!--752x480 MT9V034 image sensor, only 64x64 pixels used-->
<sensor name="PX4Flow" type="camera">
<always_on>true</always_on>
<update_rate>100.0</update_rate>
<visualize>true</visualize>
<topic>/px4flow</topic>
<camera>
<horizontal_fov>0.088</horizontal_fov>
<image>
<width>64</width>
<height>64</height>
<format>L8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.001</stddev>
</noise>
</camera>
<plugin name="opticalflow_plugin" filename="libgazebo_opticalFlow_plugin.so">
<robotNamespace></robotNamespace>
</plugin>
</sensor>
</link>
</model>
lidar
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="lidar">
<link name="link">
<inertial>
<pose>0 0 0 0 -0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>2.1733e-6</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.1733e-6</iyy>
<iyz>0</iyz>
<izz>1.8e-7</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder><radius>0.006</radius><length>0.05</length></cylinder>
</geometry>
<material>
<script>Gazebo/Black</script>
</material>
</visual>
<sensor name="laser" type="ray">
<pose>0 0 0 0 -1.570896 0</pose>
<ray>
<scan>
<horizontal>
<samples>1</samples>
<resolution>1</resolution>
<min_angle>-0</min_angle>
<max_angle>0</max_angle>
</horizontal>
</scan>
<range>
<min>0.06</min>
<max>25</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="LaserPlugin" filename="libgazebo_lidar_plugin.so"/>
<robotNamespace></robotNamespace>
<always_on>1</always_on>
<update_rate>20</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</sdf>
</sdf>
camera
<?xml version="1.0" ?>
<sdf version="1.5">
<model name="camera">
<pose>0 0 0.05 0 0 0</pose>
<link name="link">
<inertial>
<mass>0.1</mass>
<inertia>
<ixx>0.000166667</ixx>
<iyy>0.000166667</iyy>
<izz>0.000166667</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<box>
<size>0.1 0.1 0.1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>-0.01 -0.01 -0.01</size>
</box>
</geometry>
</visual>
<sensor name="camera" type="camera">
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>320</width>
<height>240</height>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<visualize>true</visualize>
</sensor>
</link>
</model>
</sdf>
Here is the final model after adding models above. But I am unable to have camera model attach to it.
irisoptflow
<sdf version='1.5'>
<model name='iris_opt_flow'>
<include>
<uri>model://iris</uri>
</include>
<include>
<uri>model://lidar</uri>
<pose>-0.12 0 0 0 3.1415 0</pose>
</include>
<joint name="lidar_joint" type="revolute">
<child>lidar::link</child>
<parent>iris::base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
<include>
<uri>model://flow_cam</uri>
<pose>-0.12 0.05 0 0 1.5708 1.5708</pose>
</include>
<joint name="flow_joint" type="revolute">
<child>camera::link</child>
<parent>iris::base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
<include>
<uri>model://camera</uri>
<pose>-.5 0.01 1 0 1.5708 1.5708</pose>
</include>
<joint name="camera_joint" type="revolute">
<child>camera::link</child>
<parent>iris::base_link</parent>
<axis>
<xyz>0 0 1</xyz>
<limit>
<upper>0</upper>
<lower>0</lower>
</limit>
</axis>
</joint>
</model>
</sdf>
Here is the result:
Asked by Vinh K on 2017-04-10 13:05:47 UTC
Answers
I believe you forgot to specify model name in your include
tags, so joints can't find their parents or children and don't glue them together
what you're doing :
<include>
<uri>model://lidar</uri>
<pose>-0.12 0 0 0 3.1415 0</pose>
</include>
what to try:
<include>
<uri>model://lidar</uri>
<pose>-0.12 0 0 0 3.1415 0</pose>
<name> lidar </name>
</include>
etc.
Asked by eugene-katsevman on 2017-04-11 15:56:05 UTC
Comments
why do you use
revolute
joints with zero lower and upper? why notfixed
?Asked by eugene-katsevman on 2017-04-11 15:58:37 UTC