Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
38 changes: 38 additions & 0 deletions nextage_description/urdf/nxo_gz.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
<?xml version="1.0"?>
<robot name="NextageOpenGz"
xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:include filename="$(find nextage_description)/urdf/NextageOpen.urdf" />
<xacro:include filename="$(find nextage_description)/urdf/nxo_gz_camera.xacro" />

<xacro:property name="M_PI" value="3.1415926535897931" />
<xacro:property name="jnt_head_camera_displacement_x" value="0.0175" />
<xacro:property name="jnt_head_camera_displacement_y" value="0.0725" />
<xacro:property name="jnt_head_camera_displacement_z" value="0.105" />
<xacro:property name="jnt_head_camera_rot_y" value="0.25" />
<xacro:property name="link_head_camera_rot_z" value="0.05" />

<!-- NOTE: The poses of headmount cameras are NOT precisely adjusted to
the 3D model nor the actual hardware config. These configs
are meant for a rapid prototyping only. If you need precise
configuration, please go ahead modify the following, then
(if possible) send a patch to https://github.com/tork-a/rtmros_nextage/pulls
so that other developers and users can use (and possible improve).
-->
<xacro:camera_joint_link_gzplugin
camera_name="L_HEADMOUNT_CAMERA" link_parent="HEAD_JOINT1_Link"
jnt_displacement_x="${jnt_head_camera_displacement_x}" jnt_displacement_y="${jnt_head_camera_displacement_y}" jnt_displacement_z="${jnt_head_camera_displacement_z}"
jnt_rotation_x="0" jnt_rotation_y="${jnt_head_camera_rot_y}" jnt_rotation_z="0"
link_displacement_x="0.0325" link_displacement_y="0" link_displacement_z="0"
link_rotation_x="0" link_rotation_y="${M_PI/2}" link_rotation_z="-${link_head_camera_rot_z}" />

<xacro:camera_joint_link_gzplugin
camera_name="R_HEADMOUNT_CAMERA" link_parent="HEAD_JOINT1_Link"
jnt_displacement_x="${jnt_head_camera_displacement_x}" jnt_displacement_y="-${jnt_head_camera_displacement_y}" jnt_displacement_z="${jnt_head_camera_displacement_z}"
jnt_rotation_x="0" jnt_rotation_y="${jnt_head_camera_rot_y}" jnt_rotation_z="0"
link_displacement_x="0.0325" link_displacement_y="0" link_displacement_z="0"
link_rotation_x="0" link_rotation_y="${M_PI/2}" link_rotation_z="${link_head_camera_rot_z}" />

<!-- TODO hand cameras can be added here with the very similar code as
headmount cameras. -->
</robot>
77 changes: 77 additions & 0 deletions nextage_description/urdf/nxo_gz_camera.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,77 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="M_PI" value="3.1415926535897931" />

<!-- Immitate two head-mount cameras, each of which are not stereo camera
by themselves but are made to function as stereo by launch file https://github.com/tork-a/rtmros_nextage/blob/indigo-devel/nextage_ros_bridge/launch/nextage_ueye_stereo.launch
Values in Gazebo plugin are originally copied from http://gazebosim.org/tutorials?tut=ros_gzplugins#camera
and only partially tailored as of May 2017 -->

<!-- Adding camera for simulation -->
<xacro:macro name="camera_joint_link_gzplugin"
params="camera_name link_parent jnt_displacement_x jnt_displacement_y jnt_displacement_z jnt_rotation_x jnt_rotation_y jnt_rotation_z link_displacement_x link_displacement_y link_displacement_z link_rotation_x link_rotation_y link_rotation_z">
<joint name="${camera_name}" type="fixed">
<origin
xyz="${jnt_displacement_x} ${jnt_displacement_y} ${jnt_displacement_z}"
rpy="${jnt_rotation_x} ${jnt_rotation_y} ${jnt_rotation_z}" />
<parent link="${link_parent}" />
<child link="${camera_name}_Link" />
</joint>
<link name="${camera_name}_Link">
<visual>
<origin
xyz="${link_displacement_x} ${link_displacement_y} ${link_displacement_z}"
rpy="${link_rotation_x} ${link_rotation_y} ${link_rotation_z}" />
<geometry>
<cylinder length="0.01" radius="0.015" />
</geometry>
<material name="blue" />
</visual>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0" />
<mass value="1" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
</link>
<gazebo reference="${camera_name}_Link">
<sensor type="camera" name="${camera_name}">
<update_rate>30.0</update_rate>
<camera name="${camera_name}">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>800</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.1</near>
<far>30</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_name}</cameraName>
<imageTopicName>image_raw</imageTopicName>
<cameraInfoTopicName>camera_info</cameraInfoTopicName>
<frameName>${camera_name}_Link_frame</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>
</xacro:macro>
</robot>
106 changes: 4 additions & 102 deletions nextage_gazebo/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,133 +1,35 @@
cmake_minimum_required(VERSION 2.8.3)
project(nextage_gazebo)

## 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 COMPONENTS
gazebo_ros
gazebo_ros_control
nextage_description
rostest
)

## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
# catkin_python_setup()

################################################
## Declare ROS dynamic reconfigure parameters ##
################################################

## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed

## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if you package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES nextage_gazebo
# CATKIN_DEPENDS gazebo_ros gazebo_ros_control nextage_description
# DEPENDS system_lib
)

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
# include_directories(include)
include_directories(
${catkin_INCLUDE_DIRS}
)

## Declare a C++ library
# add_library(nextage_gazebo
# src/${PROJECT_NAME}/nextage_gazebo.cpp
# )

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(nextage_gazebo ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Declare a C++ executable
# add_executable(nextage_gazebo_node src/nextage_gazebo_node.cpp)

## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(nextage_gazebo_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Specify libraries to link a library or executable target against
# target_link_libraries(nextage_gazebo_node
# ${catkin_LIBRARIES}
# )

#############
## Install ##
#############

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
install(PROGRAMS
scripts/go_initial.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

## Mark executables and/or libraries for installation
# install(TARGETS nextage_gazebo nextage_gazebo_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )

## Mark other files for installation (e.g. launch and bag files, etc.)
install(DIRECTORY config launch model test
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
USE_SOURCE_PERMISSIONS
)

#############
## Testing ##
#############

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_nextage_gazebo.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()

add_rostest(test/gz.test) # important to have one gz.test files, becuase running gazebo parallely makes trouble on port settings

if (CATKIN_ENABLE_TESTING)
find_package(catkin REQUIRED COMPONENTS rostest)
add_rostest(test/gz.test) # important to have one gz.test files, becuase running gazebo parallely makes trouble on port settings
endif()
Loading