Skip to content
Snippets Groups Projects
Commit aebd6b5e authored by dabaldassi's avatar dabaldassi
Browse files

put the real icpr_robotsimu back

parent d11e157c
Branches
No related tags found
No related merge requests found
......@@ -7,9 +7,7 @@ project(icpr_robotsimu)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED
laser_assembler
sensor_msgs)
find_package(catkin REQUIRED laser_assembler sensor_msgs)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
......
......@@ -5,4 +5,3 @@ joint_state_controller:
laser_velocity_controller:
type: velocity_controllers/JointVelocityController
joint: laser_joint
pid: {p: 1, i: 1, d: 1}
\ No newline at end of file
<?xml version="1.0"?>
<launch>
<rosparam file="$(find icpr_robotsimu)/config/control.yaml" command="load"/>
<rosparam file="$(find icpr_robotsimu)/config/control.yaml"/>
<node name="controller_spawner"
pkg="controller_manager"
type="spawner"
respawn="false"
output="screen"
<node name="controller_spawner" pkg="controller_manager" type="spawner"
args="laser_velocity_controller joint_state_controller"/>
</launch>
......@@ -50,6 +50,7 @@
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
......
<?xml version="1.0"?>
<robot name="model" xmlns:xacro="http://ros.org/wiki/xacro">
<robot name="turtlebot" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="sensor_size" value="0.02"/>
<joint name="laser_joint" type="continuous">
<axis xyz="1 0 0" />
<origin rpy="0 0 3.14" xyz="-1.44483 0.00498 0.32338"/>
<parent link="model__link_1"/>
<axis xyz="0 1 0" />
<origin xyz="0 0 0.3" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="laser_link"/>
<!--limit lower="-1.0" upper="1.0" effort="100.0" velocity="10.0"/-->
</joint>
......@@ -35,18 +35,16 @@
</link>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<!-- <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> -->
</plugin>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so"/>
</gazebo>
<transmission name="laser_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="laser_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="laser_motor">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<hardwareInterface>VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
......
......@@ -4,7 +4,7 @@
<xacro:property name="camera_size" value="0.05" />
<xacro:property name="wheel_separation" value="0.12" />
<xacro:property name="wheel_diameter" value="0.6" />
<xacro:include filename="$(find icpr_robotsimu)/urdf/spinning_joint.urdf.xacro" />
<xacro:include filename="$(find icpr_robotsimu_results)/urdf/spinning_joint.urdf.xacro" />
<joint name="model__link_1_JOINT_2" type="revolute">
<parent link="model__link_1"/>
......
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<joint name="camera_joint" type="fixed">
<axis xyz="0 1 0" />
<origin xyz="${camera_link} 0 ${height3 - axel_offset*2}" rpy="0 0 0"/>
<parent link="link3"/>
<child link="camera_link"/>
</joint>
<!-- Camera -->
<link name="camera_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_link} ${camera_link} ${camera_link}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${camera_link} ${camera_link} ${camera_link}"/>
</geometry>
<material name="red"/>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6" />
</inertial>
</link>
<!-- camera -->
<gazebo reference="camera_link">
<sensor type="camera" name="camera1">
<update_rate>30.0</update_rate>
<camera name="head">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</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>icpr_robotsimu_results/camera1</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>
</robot>
<?xml version="1.0"?>
<robot name="model" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:property name="sensor_size" value="0.02"/>
<joint name="laser_joint" type="continuous">
<axis xyz="1 0 0" />
<origin rpy="0 0 3.14" xyz="-1.44483 0.00498 0.32338"/>
<parent link="model__link_1"/>
<child link="laser_link"/>
<!--limit lower="-1.0" upper="1.0" effort="100.0" velocity="10.0"/-->
</joint>
<link name="laser_link">
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${sensor_size} ${sensor_size} ${sensor_size}"/>
</geometry>
</collision>
<visual>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<box size="${sensor_size} ${sensor_size} ${sensor_size}"/>
</geometry>
</visual>
<inertial>
<mass value="1e-5" />
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="1e-6" ixy="0" ixz="0" iyy="1e-6" iyz="0" izz="1e-6"/>
</inertial>
</link>
<gazebo>
<plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
<!-- <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType> -->
</plugin>
</gazebo>
<transmission name="laser_transmission">
<type>transmission_interface/SimpleTransmission</type>
<joint name="laser_joint">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="laser_motor">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</robot>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment