-
Notifications
You must be signed in to change notification settings - Fork 154
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Merge pull request #113 from berndpfrommer/humble-devel-new
new driver for ROS2
- Loading branch information
Showing
81 changed files
with
4,160 additions
and
4,730 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,31 +1,22 @@ | ||
# flir_camera_driver | ||
|
||
This repository contains packages for FlirImaging's line of cameras. This repositories intent is to make use of Flir's newly developed SDK: Spinnaker. The camera driver is an evolution of pointgrey_camera_driver. It has been updated to use the new methods provided by the SDK. | ||
This repository contains ROS packages for cameras made by FLIR Imaging (formerly known as PointGrey). | ||
|
||
## Packages | ||
|
||
### Spinnaker Camera Driver | ||
The camera driver supports USB3 and GIGE cameras are planned. Note thats support for FireWire cameras is dropped in this SDK. The driver has been tested with a Blackfly S and Chameleon 3 camera. Differences between cameras requires that each camera model needs a customized interface class. If your camera type is not included, consider contributing the interface by referring to the section bellow. | ||
|
||
##### Contributing | ||
Due to differences in parameter naming the configuration is separated from the main library. `camera.cpp` contains the base class `Camera` which can be extended to accommodate different cameras. The base class is based on BlackFly S and `cm3.cpp` extends it adding support for Chameleon3. To add a camera create a new derived class of `Camera` and add the model name to the check in `SpinnakerCamera::connect`. | ||
|
||
When contributing make sure the travis job suceeds and please use [roscpp_code_format](https://github.com/davetcoleman/roscpp_code_format) to format your code. | ||
|
||
## Licence | ||
ROS-compatible Camera drivers originally provided by NREC, part of Carnegie Mellon University's robotics institute. | ||
These drives are included along with modifications of the standard ros image messages that enable HDR and physics based vision. | ||
|
||
This code was originally developed by the National Robotics Engineering Center (NREC), part of the Robotics Institute at Carnegie Mellon University. Its development was funded by DARPA under the LS3 program and submitted for public release on June 7th, 2012. Release was granted on August, 21st 2012 with Distribution Statement "A" (Approved for Public Release, Distribution Unlimited). | ||
|
||
This software is released under a BSD license: | ||
|
||
Copyright (c) 2012, Carnegie Mellon University. All rights reserved. | ||
Copyright (c) 2018, Clearpath Robotics, Inc., All rights reserved. | ||
|
||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: | ||
|
||
Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. | ||
Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. | ||
Neither the name of the Carnegie Mellon University nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. | ||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. | ||
### spinnaker_camera_driver | ||
The camera driver supports USB3 and GIGE cameras. The driver has been | ||
successfully used for Blackfly, Blackfly S, Chameleon, and Grasshopper | ||
cameras, but should support any FLIR camera that is based on the | ||
Spinnaker SDK. See the | ||
[spinnaker_camera_driver](spinnaker_camera_driver/README.md) for more. | ||
This software is issued under the Apache License Version 2.0 and BSD | ||
|
||
### flir_camera_msgs | ||
Package with with [image exposure and control messages](flir_camera_msgs/README.md). | ||
These are used by the [spinnaker_camera_driver](spinnaker_camera_driver/README.md). | ||
This software is issued under the Apache License Version 2.0. | ||
|
||
### flir_camera_description | ||
Package with [meshes and urdf](flir_camera_description/README.md) files. | ||
This software is released under a BSD license. |
This file was deleted.
Oops, something went wrong.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,10 +1,20 @@ | ||
cmake_minimum_required(VERSION 3.0.2) | ||
cmake_minimum_required(VERSION 3.5) | ||
project(flir_camera_description) | ||
|
||
find_package(catkin REQUIRED) | ||
# find dependencies | ||
find_package(ament_cmake REQUIRED) | ||
find_package(urdf REQUIRED) | ||
find_package(xacro REQUIRED) | ||
find_package(robot_state_publisher REQUIRED) | ||
|
||
catkin_package() | ||
|
||
install(DIRECTORY meshes urdf | ||
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} | ||
install( | ||
DIRECTORY launch meshes urdf | ||
DESTINATION share/${PROJECT_NAME} | ||
) | ||
|
||
if(BUILD_TESTING) | ||
find_package(ament_lint_auto REQUIRED) | ||
ament_lint_auto_find_test_dependencies() | ||
endif() | ||
|
||
ament_package() |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,26 @@ | ||
Redistribution and use in source and binary forms, with or without | ||
modification, are permitted provided that the following conditions | ||
are met: | ||
|
||
* Redistributions of source code must retain the above copyright | ||
notice, this list of conditions and the following disclaimer. | ||
* Redistributions in binary form must reproduce the above | ||
copyright notice, this list of conditions and the following | ||
disclaimer in the documentation and/or other materials provided | ||
with the distribution. | ||
* Neither the name of copyright holder nor the names of its | ||
contributors may be used to endorse or promote products derived | ||
from this software without specific prior written permission. | ||
|
||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS | ||
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE | ||
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, | ||
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, | ||
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; | ||
LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER | ||
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT | ||
LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN | ||
ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE | ||
POSSIBILITY OF SUCH DAMAGE. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,19 @@ | ||
# flir_camera_description | ||
|
||
![banner image](images/blackfly_s_description.png) | ||
|
||
This package contains urdf files and meshes for FLIR cameras. | ||
|
||
## How to use | ||
Install this package like any other ROS package, then launch the demo: | ||
``` | ||
ros2 launch flir_camera_description demo.launch.py | ||
ros2 run rviz2 rviz2 | ||
``` | ||
In rviz, add a "RobotModel" and set the topic to "robot_description". | ||
|
||
|
||
## License: | ||
Licensed under BSD License. | ||
Copyright (c) 2012, Carnegie Mellon University. All rights reserved. | ||
Copyright (c) 2018, Clearpath Robotics, Inc., All rights reserved. |
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,92 @@ | ||
# Copyright 2021 Clearpath Robotics, Inc. | ||
# Copyright 2023 Bernd Pfrommer | ||
# | ||
# Licensed under the Apache License, Version 2.0 (the "License"); | ||
# you may not use this file except in compliance with the License. | ||
# You may obtain a copy of the License at | ||
# | ||
# http://www.apache.org/licenses/LICENSE-2.0 | ||
# | ||
# Unless required by applicable law or agreed to in writing, software | ||
# distributed under the License is distributed on an "AS IS" BASIS, | ||
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. | ||
# See the License for the specific language governing permissions and | ||
# limitations under the License. | ||
# | ||
# @author Roni Kreinin (rkreinin@clearpathrobotics.com) | ||
# @author Bernd Pfrommer (bernd@pfrommer.us) | ||
|
||
|
||
from ament_index_python.packages import get_package_share_directory | ||
|
||
from launch import LaunchDescription | ||
from launch.actions import DeclareLaunchArgument | ||
from launch.substitutions import Command, PathJoinSubstitution | ||
from launch.substitutions.launch_configuration import LaunchConfiguration | ||
|
||
from launch_ros.actions import Node | ||
|
||
|
||
ARGUMENTS = [ | ||
DeclareLaunchArgument('model', default_value='flir_blackfly_s', | ||
choices=['flir_blackfly_s'], | ||
description='camera model'), | ||
DeclareLaunchArgument('use_sim_time', default_value='false', | ||
choices=['true', 'false'], | ||
description='use_sim_time'), | ||
DeclareLaunchArgument('camera_name', default_value=LaunchConfiguration('model'), | ||
description='camera name'), | ||
DeclareLaunchArgument('namespace', default_value=LaunchConfiguration('camera_name'), | ||
description='camera namespace'), | ||
] | ||
|
||
|
||
def generate_launch_description(): | ||
camera_description = get_package_share_directory('flir_camera_description') | ||
xacro_file = PathJoinSubstitution([camera_description, 'urdf', 'demo.urdf.xacro']) | ||
namespace = LaunchConfiguration('namespace') | ||
robot_state_publisher = Node( | ||
package='robot_state_publisher', | ||
executable='robot_state_publisher', | ||
name='robot_state_publisher', | ||
output='screen', | ||
parameters=[ | ||
{'use_sim_time': LaunchConfiguration('use_sim_time')}, | ||
{'robot_description': Command([ | ||
'xacro', ' ', xacro_file, ' ', | ||
'model:=', LaunchConfiguration('model'), ' ', | ||
'namespace:=', namespace])}, | ||
], | ||
remappings=[ | ||
('/tf', 'tf'), | ||
('/tf_static', 'tf_static') | ||
] | ||
) | ||
|
||
joint_state_publisher = Node( | ||
package='joint_state_publisher', | ||
executable='joint_state_publisher', | ||
name='joint_state_publisher', | ||
output='screen', | ||
parameters=[{'use_sim_time': LaunchConfiguration('use_sim_time')}], | ||
remappings=[ | ||
('/tf', 'tf'), | ||
('/tf_static', 'tf_static') | ||
] | ||
) | ||
|
||
world_tf_publisher = Node( | ||
package="tf2_ros", | ||
executable="static_transform_publisher", | ||
arguments=['--x', '0', '--y', '0', '--z', '1', '--yaw', '0', | ||
'--pitch', '0', '--roll', '0', | ||
'--frame-id', 'world', '--child-frame-id', 'camera_frame']) | ||
|
||
# Define LaunchDescription variable | ||
ld = LaunchDescription(ARGUMENTS) | ||
# Add nodes to LaunchDescription | ||
ld.add_action(robot_state_publisher) | ||
ld.add_action(joint_state_publisher) | ||
ld.add_action(world_tf_publisher) | ||
|
||
return ld |
File renamed without changes.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,15 +1,22 @@ | ||
<?xml version="1.0"?> | ||
<package format="2"> | ||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> | ||
<package format="3"> | ||
<name>flir_camera_description</name> | ||
<version>0.2.5</version> | ||
<description>URDF descriptions for Flir cameras</description> | ||
|
||
<version>1.0.0</version> | ||
<description>FLIR camera Description package</description> | ||
<maintainer email="lcamero@clearpathrobotics.com">Luis Camero</maintainer> | ||
|
||
<license>BSD</license> | ||
|
||
<buildtool_depend>catkin</buildtool_depend> | ||
<exec_depend>robot_state_publisher</exec_depend> | ||
<exec_depend>urdf</exec_depend> | ||
<exec_depend>xacro</exec_depend> | ||
<buildtool_depend>ament_cmake</buildtool_depend> | ||
|
||
<depend>urdf</depend> | ||
<depend>robot_state_publisher</depend> | ||
<depend>xacro</depend> | ||
|
||
<test_depend>ament_lint_auto</test_depend> | ||
<test_depend>ament_lint_common</test_depend> | ||
|
||
<export> | ||
<build_type>ament_cmake</build_type> | ||
</export> | ||
</package> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,20 @@ | ||
<?xml version="1.0"?> | ||
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="$(arg model)"> | ||
|
||
<!-- define the material color --> | ||
<material name="dark_grey"> | ||
<color rgba="0.5 0.5 0.5 1.0"/> | ||
</material> | ||
|
||
<!-- this include provides the macro definition used below --> | ||
<xacro:include filename="$(find flir_camera_description)/urdf/$(arg model).urdf.xacro"/> | ||
|
||
<xacro:property name="model" value="$(arg model)"/> | ||
|
||
<!-- if more models are defined, add them here --> | ||
<xacro:if value="${model =='flir_blackfly_s'}"> | ||
<xacro:flir_blackfly_s name="$(arg model)" frame="camera_frame"> | ||
</xacro:flir_blackfly_s> | ||
</xacro:if> | ||
|
||
</robot> |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.