├── .travis.yml
├── LICENSE
├── README.md
├── ca_description
├── CHANGELOG.rst
├── CMakeLists.txt
├── README.md
├── launch
│ ├── create_1.launch
│ ├── create_2.launch
│ └── roomba_400.launch
├── meshes
│ ├── create_1.dae
│ ├── create_1.tga
│ └── create_2.dae
├── package.xml
└── urdf
│ ├── create_1.urdf
│ ├── create_1.urdf.xacro
│ ├── create_1_gazebo.urdf
│ ├── create_1_gazebo.urdf.xacro
│ ├── create_2.urdf
│ ├── create_2.urdf.xacro
│ ├── create_2_gazebo.urdf
│ ├── create_2_gazebo.urdf.xacro
│ ├── create_base.urdf.xacro
│ └── create_base_gazebo.urdf.xacro
├── ca_driver
├── CHANGELOG.rst
├── CMakeLists.txt
├── README.md
├── config
│ └── default.yaml
├── include
│ └── create_driver
│ │ └── create_driver.hpp
├── launch
│ ├── create_1.launch
│ ├── create_2.launch
│ └── roomba_400.launch
├── package.xml
└── src
│ └── create_driver.cpp
├── ca_msgs
├── CHANGELOG.rst
├── CMakeLists.txt
├── msg
│ ├── Bumper.msg
│ ├── ChargingState.msg
│ ├── DefineSong.msg
│ ├── Mode.msg
│ └── PlaySong.msg
└── package.xml
├── ca_tools
├── CHANGELOG.rst
├── CMakeLists.txt
├── config
│ ├── log710.yaml
│ └── xbox360.yaml
├── launch
│ └── joy_teleop.launch
└── package.xml
└── create_autonomy
├── CHANGELOG.rst
├── CMakeLists.txt
└── package.xml
/.travis.yml:
--------------------------------------------------------------------------------
1 | sudo: required
2 | dist: trusty
3 | # Force travis to use its minimal image with default Python settings
4 | language: generic
5 | compiler:
6 | - gcc
7 | env:
8 | global:
9 | - CATKIN_WS=~/catkin_ws
10 | - CATKIN_WS_SRC=${CATKIN_WS}/src
11 | - CI_ROS_DISTRO="indigo"
12 | install:
13 | - sudo sh -c 'echo "deb http://packages.ros.org/ros/ubuntu trusty main" > /etc/apt/sources.list.d/ros-latest.list'
14 | - wget http://packages.ros.org/ros.key -O - | sudo apt-key add -
15 | - sudo apt-get update -qq
16 | - sudo apt-get install -qq -y python-rosdep python-catkin-tools
17 | - sudo rosdep init
18 | - rosdep update
19 | # Use rosdep to install all dependencies (including ROS itself)
20 | - rosdep install --from-paths ./ -i -y --rosdistro $CI_ROS_DISTRO
21 | script:
22 | - source /opt/ros/$CI_ROS_DISTRO/setup.bash
23 | - mkdir -p $CATKIN_WS_SRC
24 | - ln -s $TRAVIS_BUILD_DIR $CATKIN_WS_SRC
25 | - cd $CATKIN_WS
26 | - catkin init
27 | - catkin config --install
28 | # Build [and Install] packages
29 | - catkin build --limit-status-rate 0.1 --no-notify -DCMAKE_BUILD_TYPE=Release
30 | # Run tests
31 | - catkin run_tests
32 | - catkin_test_results build
33 | # Lint package files
34 | - sudo apt-get install python-catkin-lint
35 | - catkin lint -W2 --strict --explain src
36 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | Copyright (c) 2015, Jacob Perron (Autonomy Lab, Simon Fraser University)
2 | All rights reserved.
3 |
4 | Redistribution and use in source and binary forms, with or without
5 | modification, are permitted provided that the following conditions are met:
6 | * Redistributions of source code must retain the above copyright notice,
7 | this list of conditions and the following disclaimer.
8 | * Redistributions in binary form must reproduce the above copyright notice,
9 | this list of conditions and the following disclaimer in the
10 | documentation and/or other materials provided with the distribution.
11 | * Neither the name of Autonomy Lab nor the names of its contributors may
12 | be used to endorse or promote products derived from this software without
13 | specific prior written permission.
14 |
15 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18 | ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
19 | LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20 | CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21 | SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22 | INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23 | CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24 | ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25 | POSSIBILITY OF SUCH DAMAGE.
26 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # create_autonomy
2 |
3 | [ROS](http://ros.org) driver for iRobot [Create 1 and 2](http://www.irobot.com/About-iRobot/STEM/Create-2.aspx).
4 | This package wraps the C++ library [libcreate][libcreate], which uses iRobot's [Open Interface Specification][oi_spec].
5 |
6 |
7 | * ROS wiki page: http://wiki.ros.org/create_autonomy
8 | * Support: [ROS Answers (tag: create_autonomy)](http://answers.ros.org/questions/scope:all/sort:activity-desc/tags:create_autonomy/page:1/)
9 | * Author: [Jacob Perron](http://jacobperron.ca) ([Autonomy Lab](http://autonomylab.org), [Simon Fraser University](http://www.sfu.ca))
10 |
11 | ## Build Status
12 |
13 | TravisCI (Ubuntu _Trusty_, ROS _Indigo_ and _Jade_)
14 | 
15 |
16 | ## Supported Robots
17 |
18 | | Model | Support |
19 | |-----------|------------|
20 | | Create 1 | Yes |
21 | | Create 2 _(firmware >= 3.2.6)_ | Yes |
22 | | Roomba Original Series | No |
23 | | Roomba 400 Series | Yes |
24 | | Roomba 500 Series | Yes * |
25 | | Roomba 600 Series | Yes * |
26 | | Roomba 700 Series | Yes + |
27 | | Roomba 800 Series | Yes + |
28 | | Roomba 900 Series | No * |
29 |
30 | _+ Verified by third-party. Please note [Odometry Issue #28](https://github.com/AutonomyLab/create_autonomy/issues/32)_
31 | _* Not verified. Anyone who is able to verify that this driver works or not is encouraged to contact [Jacob](https://jacobperron.ca) with their findings or open an issue._
32 |
33 | ## Features
34 |
35 | | Feature | Status |
36 | |-------------------|---------------|
37 | | Odometry | Available |
38 | | Safe mode | Planned [#13](https://github.com/AutonomyLab/create_autonomy/issues/13) |
39 | | Clean demo | Planned [#14](https://github.com/AutonomyLab/create_autonomy/issues/14) |
40 | | Dock demo | Available |
41 | | Drive wheels | N/A |
42 | | Drive (v,w) | Available |
43 | | Brush motors | Planned [#15](https://github.com/AutonomyLab/create_autonomy/issues/15) |
44 | | LEDs | Available |
45 | | Digit LEDs | Available |
46 | | Sound | Available |
47 | | Wheeldrop | Available |
48 | | Bumpers | Available |
49 | | Cliff sensor | Planned [#22](https://github.com/AutonomyLab/create_autonomy/issues/22) |
50 | | Dirt detect | N/A |
51 | | Omni IR sensor | Available |
52 | | Left IR sensor | N/A |
53 | | Right IR sensor | N/A |
54 | | Battery info | Available |
55 | | Light sensors | Available |
56 | | **_Diagnostics_** | |
57 | | Corrupt packets | Planned |
58 | | Physical tests | Planned |
59 | | Overcurrent info | Planned |
60 |
61 | ## Install
62 |
63 | #### Prerequisites
64 |
65 | * Internet connection
66 | * [ROS 2](https://index.ros.org/doc/ros2/Installation/) _Crystal_
67 |
68 | #### Compiling
69 |
70 | 1. Create a colcon workspace
71 | ``` bash
72 | $ cd ~
73 | $ mkdir -p create_ws/src
74 | $ cd create_ws
75 | $ colcon build
76 | ```
77 |
78 | 2. Clone this repo
79 | ``` bash
80 | $ cd ~/create_ws/src
81 | $ git clone https://github.com/AutonomyLab/create_autonomy.git
82 | ```
83 |
84 | 3. Install dependencies
85 | ``` bash
86 | $ cd ~/create_ws
87 | $ rosdep update
88 | $ rosdep install --from-paths src -i
89 | ```
90 |
91 | 4. Build
92 | ``` bash
93 | $ cd ~/create_ws
94 | $ colcon build
95 | ```
96 | #### USB Permissions
97 | 5. In order to connect to Create over USB, ensure your user is in the dialout group
98 | ``` bash
99 | $ sudo usermod -a -G dialout $USER
100 | ```
101 |
102 | 6. Logout and login for permission to take effect
103 |
104 | ## Running the driver
105 |
106 | ### Setup
107 |
108 | 1. After compiling from source, don't forget to source your workspace:
109 | ``` bash
110 | $ source ~/create_ws/install/local_setup.bash
111 | ```
112 |
113 | 2. Connect computer to Create's 7-pin serial port
114 | - If using Create 1, ensure that nothing is connected to Create's DB-25 port
115 |
116 | 3. Launch one of the existing launch files or adapt them to create your own.
117 |
118 | ### Launch files
119 |
120 | For Create 2 (Roomba 600/700 series):
121 | ``` bash
122 | $ ros2 launch ca_driver create_2.launch.py
123 | ```
124 |
125 | For Create 1 (Roomba 500 series):
126 | ``` bash
127 | $ ros2 launch ca_driver create_1.launch.py
128 | ```
129 |
130 | For Roomba 400 series:
131 | ``` bash
132 | $ ros2 launch ca_driver roomba_400.launch.py
133 | ```
134 |
135 | #### Launch file arguments
136 |
137 | * **config** - Absolute path to a configuration file (YAML). Default: `ca_driver/config/default.yaml`
138 | * **desc** - Enable robot description (URDF/mesh). Default: `true`
139 |
140 | For example, if you would like to disable the robot description and provide a custom configuration file:
141 |
142 | ```bash
143 | $ ros2 launch ca_driver create_2.launch.py config:=/abs/path/to/config.yaml desc:=false
144 | ```
145 |
146 | ### Parameters
147 |
148 | Name | Description | Default
149 | --------------|--------------|----------
150 | `dev` | Device path of robot | `/dev/ttyUSB0`
151 | `base_frame` | The robot's base frame ID | `base_footprint`
152 | `odom_frame` | The robot's odometry frame ID | `odom`
153 | `latch_cmd_duration` | If this many seconds passes without receiving a velocity command the robot stops | `0.2`
154 | `loop_hz` | Frequency of internal update loop | `10.0`
155 | `publish_tf` | Publish the transform from `odom_frame` to `base_frame` | `true`
156 | `robot_model` | The type of robot being controlled (supported values: `ROOMBA_400`, `CREATE_1` and `CREATE_2`) | `CREATE_2`
157 | `baud` | Serial baud rate | Inferred based on robot model, but is overwritten upon providing a value
158 |
159 | ### Publishers
160 |
161 | Topic | Description | Type
162 | -------------|--------------|------
163 | `battery/capacity` | The estimated charge capacity of the robot's battery (Ah) | [std_msgs/Float32][float32]
164 | `battery/charge` | The current charge of the robot's battery (Ah) | [std_msgs/Float32][float32]
165 | `battery/charge_ratio` | Charge / capacity | [std_msgs/Float32][float32]
166 | `battery/charging_state` | The chargins state of the battery | [ca_msgs/ChargingState][chargingstate_msg]
167 | `battery/current` | Current flowing through the robot's battery (A). Positive current implies charging | [std_msgs/Float32][float32]
168 | `battery/temperature` | The temperature of the robot's battery (degrees Celsius) | [std_msgs/Int16][int16]
169 | `battery/voltage` | Voltage of the robot's battery (V) | [std_msgs/Float32][float32]
170 | `bumper` | Bumper state message (including light sensors on bumpers) | [ca_msgs/Bumper][bumper_msg]
171 | `clean_button` | 'clean' button is pressed ('play' button for Create 1) | [std_msgs/Empty][empty]
172 | `day_button` | 'day' button is pressed | [std_msgs/Empty][empty]
173 | `hour_button` | 'hour' button is pressed | [std_msgs/Empty][empty]
174 | `minute_button` | 'minute' button is pressed | [std_msgs/Empty][empty]
175 | `dock_button` | 'dock' button is pressed ('advance' button for Create 1) | [std_msgs/Empty][empty]
176 | `spot_button` | 'spot' button is pressed | [std_msgs/Empty][empty]
177 | `ir_omni` | The IR character currently being read by the omnidirectional receiver. Value 0 means no character is being received | [std_msgs/UInt16][uint16]
178 | `joint_states` | The states (position, velocity) of the drive wheel joints | [sensor_msgs/JointState][jointstate_msg]
179 | `mode` | The current mode of the robot (See [OI Spec][oi_spec] for details)| [ca_msgs/Mode][mode_msg]
180 | `odom` | Robot odometry according to wheel encoders | [nav_msgs/Odometry][odometry]
181 | `wheeldrop` | At least one of the drive wheels has dropped | [std_msgs/Empty][empty]
182 | `/tf` | The transform from the `odom` frame to `base_footprint`. Only if the parameter `publish_tf` is `true` | [tf2_msgs/TFMessage](http://docs.ros.org/jade/api/tf2_msgs/html/msg/TFMessage.html)
183 |
184 |
185 | ### Subscribers
186 |
187 | Topic | Description | Type
188 | ------------|---------------|------
189 | `cmd_vel` | Drives the robot's wheels according to a forward and angular velocity | [geometry_msgs/Twist][twist]
190 | `debris_led` | Enable / disable the blue 'debris' LED | [std_msgs/Bool][bool]
191 | `spot_led` | Enable / disable the 'spot' LED | [std_msgs/Bool][bool]
192 | `dock_led` | Enable / disable the 'dock' LED | [std_msgs/Bool][bool]
193 | `check_led` | Enable / disable the 'check robot` LED | [std_msgs/Bool][bool]
194 | `power_led` | Set the 'power' LED color and intensity. Accepts 1 or 2 bytes, the first represents the color between green (0) and red (255) and the second (optional) represents the intensity with brightest setting as default (255) | [std_msgs/UInt8MultiArray][uint8multiarray]
195 | `set_ascii` | Sets the 4 digit LEDs. Accepts 1 to 4 bytes, each representing an ASCII character to be displayed from left to right | [std_msgs/UInt8MultiArray][uint8multiarray]
196 | `dock` | Activates the demo docking behaviour. Robot enters _Passive_ mode meaning the user loses control (See [OI Spec][oi_spec]) | [std_msgs/Empty][empty]
197 | `undock` | Switches robot to _Full_ mode giving control back to the user | [std_msgs/Empty][empty]
198 | `define_song` | Define a song with up to 16 notes. Each note is described by a MIDI note number and a float32 duration in seconds. The longest duration is 255/64 seconds. You can define up to 4 songs (See [OI Spec][oi_spec]) | [ca_msgs/DefineSong][definesong_msg]
199 | `play_song` | Play a predefined song | [ca_msgs/PlaySong][playsong_msg]
200 |
201 | ## Commanding your Create
202 |
203 | You can move the robot around by sending [geometry_msgs/Twist][twist] messages to the topic `cmd_vel`:
204 |
205 | ```
206 | linear.x (+) Move forward (m/s)
207 | (-) Move backward (m/s)
208 | angular.z (+) Rotate counter-clockwise (rad/s)
209 | (-) Rotate clockwise (rad/s)
210 | ```
211 | #### Velocity limits
212 |
213 | ` -0.5 <= linear.x <= 0.5` and `-4.25 <= angular.z <= 4.25`
214 |
215 | ### Teleoperation
216 |
217 | `ca_tools` comes with a launch file for teleoperating Create with a joystick.
218 |
219 | ``` bash
220 | $ roslaunch ca_tools joy_teleop.launch [joy_config:=xbox360]
221 | ```
222 |
223 | There exists configuration files for the [Xbox 360 wired controller](https://www.amazon.ca/Microsoft-Xbox-360-Wired-Controller/dp/B003ZSN600) and the [Logitech F710 controller](http://gaming.logitech.com/en-ca/product/f710-wireless-gamepad). You can adapt these files for your preferred joystick configuration.
224 |
225 | ## Contributions
226 |
227 | Contributing to the development and maintenance of _create\_autonomy_ is encouraged. Feel free to open issues or create pull requests on [GitHub](https://github.com/AutonomyLab/create_autonomy).
228 |
229 | ### Contributors
230 |
231 | * [Michael Browne](http://brownem.engineer/)
232 | - Confirms driver works with Roomba 700 and 800 series.
233 | * [Clyde McQueen](https://github.com/clydemcqueen)
234 | - Added support for sound ([#37](https://github.com/AutonomyLab/create_autonomy/pull/37)).
235 | * [Ben Wolsieffer](https://github.com/lopsided98)
236 | - Added JointState publisher for wheels ([#26](https://github.com/AutonomyLab/create_autonomy/pull/26)).
237 | - Added Create 1 description ([#27](https://github.com/AutonomyLab/create_autonomy/pull/27)).
238 |
239 | [libcreate]: https://github.com/AutonomyLab/libcreate
240 | [oi_spec]: https://www.adafruit.com/datasheets/create_2_Open_Interface_Spec.pdf
241 | [odometry]: http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html
242 | [empty]: http://docs.ros.org/api/std_msgs/html/msg/Empty.html
243 | [uint16]: http://docs.ros.org/api/std_msgs/html/msg/UInt16.html
244 | [int16]: http://docs.ros.org/api/std_msgs/html/msg/Int16.html
245 | [twist]: http://docs.ros.org/api/geometry_msgs/html/msg/Twist.html
246 | [bool]: http://docs.ros.org/api/std_msgs/html/msg/Bool.html
247 | [uint8multiarray]: http://docs.ros.org/api/std_msgs/html/msg/UInt8MultiArray.html
248 | [float32]: http://docs.ros.org/api/std_msgs/html/msg/Float32.html
249 | [ca_msgs]: http://github.com/AutonomyLab/create_autonomy/tree/indigo-devel
250 | [bumper_msg]: https://github.com/AutonomyLab/create_autonomy/blob/indigo-devel/ca_msgs/msg/Bumper.msg
251 | [mode_msg]: https://github.com/AutonomyLab/create_autonomy/blob/indigo-devel/ca_msgs/msg/Mode.msg
252 | [chargingstate_msg]: https://github.com/AutonomyLab/create_autonomy/blob/indigo-devel/ca_msgs/msg/ChargingState.msg
253 | [jointstate_msg]: http://docs.ros.org/api/sensor_msgs/html/msg/JointState.html
254 | [definesong_msg]: https://github.com/AutonomyLab/create_autonomy/blob/indigo-devel/ca_msgs/msg/DefineSong.msg
255 | [playsong_msg]: https://github.com/AutonomyLab/create_autonomy/blob/indigo-devel/ca_msgs/msg/PlaySong.msg
256 |
--------------------------------------------------------------------------------
/ca_description/CHANGELOG.rst:
--------------------------------------------------------------------------------
1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2 | Changelog for package ca_description
3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4 |
5 | 1.3.0 (2018-06-10)
6 | ------------------
7 | * Migrate to package.xml format 2
8 | * Minor linting to package files.
9 | * Update install rules
10 | * Refactor launch files and expose robot base and odometry frame IDs as parameters
11 | * Refactor CMakeLists.txt and package.xml files and add missing install rules
12 | * Contributors: Jacob Perron
13 |
14 | 1.2.0 (2016-10-07)
15 | ------------------
16 | * Add support for more than two robot models and fix compiling with latest changes from libcreate.
17 | * Contributors: Ben Wolsieffer
18 |
19 | 1.1.0 (2016-07-23)
20 | ------------------
21 | * Refactor URDF to support differences between Create 1 and 2, while using a common base.
22 | * Include a mesh for the Create 1, borrowed from turtlebot_create.
23 | * Update launch files to support Create 1.
24 | * Contributors: Ben Wolsieffer
25 |
26 | 1.0.1 (2016-05-24)
27 | ------------------
28 |
29 | 1.0.0 (2016-04-01)
30 | ------------------
31 | * Add ca_description package
32 | * Contributors: Jacob Perron
33 |
--------------------------------------------------------------------------------
/ca_description/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project(ca_description)
3 |
4 | if(NOT CMAKE_CXX_STANDARD)
5 | set(CMAKE_CXX_STANDARD 14)
6 | endif()
7 |
8 | find_package(ament_cmake REQUIRED)
9 | find_package(urdf REQUIRED)
10 | find_package(xacro REQUIRED)
11 |
12 | install(DIRECTORY launch urdf meshes
13 | DESTINATION share/${PROJECT_NAME}
14 | )
15 |
16 | ament_package()
17 |
--------------------------------------------------------------------------------
/ca_description/README.md:
--------------------------------------------------------------------------------
1 | # ca_description
2 |
3 | A place for URDF models and meshes for iRobot's Create 1 and 2.
4 |
5 | ## Sources
6 |
7 | * Original URDF and Create 1 mesh: https://github.com/turtlebot/turtlebot_create
8 | * Original Create 2 mesh: https://github.com/goncabrita/roomba_robot
9 |
--------------------------------------------------------------------------------
/ca_description/launch/create_1.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/ca_description/launch/create_2.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
--------------------------------------------------------------------------------
/ca_description/launch/roomba_400.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
--------------------------------------------------------------------------------
/ca_description/meshes/create_1.tga:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/youtalk/create_autonomy/b7cbf2db7ec0995356fb913ad752c95283543419/ca_description/meshes/create_1.tga
--------------------------------------------------------------------------------
/ca_description/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | ca_description
4 | 2.0.0
5 | Robot URDF descriptions for create_autonomy
6 |
7 | Jacob Perron
8 | Yutaka Kondo
9 |
10 | BSD
11 |
12 | http://wiki.ros.org/ca_description
13 |
14 | Jacob Perron
15 |
16 | ament_cmake
17 |
18 | urdf
19 | xacro
20 | robot_state_publisher
21 |
22 |
23 | ament_cmake
24 |
25 |
26 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_1.urdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 |
151 |
152 |
153 |
154 |
155 |
156 |
184 |
185 |
186 |
187 |
188 |
189 |
190 |
191 |
192 |
193 |
194 |
195 |
196 |
197 |
198 |
199 |
200 |
201 |
202 |
203 |
204 |
205 |
206 |
207 |
208 |
209 |
210 |
211 |
212 |
213 |
214 |
215 |
216 |
217 |
218 |
219 |
220 |
221 |
222 |
223 |
224 |
225 | true
226 | 40
227 | right_wheel_joint
228 | left_wheel_joint
229 | 0.26
230 | 0.072
231 | 1.0
232 |
233 | cmd_vel
234 | odom
235 | odom
236 | base_footprint
237 |
238 |
239 | true
240 | 100.0
241 | base_link
242 | simple_controller/absolute_position
243 | 0
244 | map
245 | 0 0 0
246 | 0 0 0
247 |
248 |
249 |
250 |
251 | 1.0
252 | 1.0
253 | 1000000.0
254 | 100.0
255 | 0.001
256 | 1.0
257 |
258 |
259 | 1.0
260 | 1.0
261 | 1000000.0
262 | 100.0
263 | 0.001
264 | 1.0
265 |
266 |
267 | 0.0
268 | 0.0
269 | 1000000.0
270 | 100.0
271 | 0.001
272 | 1.0
273 |
274 |
275 | 0.0
276 | 0.0
277 | 1000000.0
278 | 100.0
279 | 0.001
280 | 1.0
281 |
282 |
283 |
284 | true
285 | 20.0
286 | 0 0 0 0 0 0
287 | false
288 |
289 |
290 |
291 | 1
292 | 1
293 | 0
294 | 0
295 |
296 |
297 |
298 | 0.0160
299 | 0.04
300 | 0.1
301 |
302 |
303 |
304 |
305 |
306 |
307 | true
308 | 20.0
309 | 0 0 0 0 0 0
310 | false
311 |
312 |
313 |
314 | 1
315 | 1
316 | 0
317 | 0
318 |
319 |
320 |
321 | 0.01
322 | 0.04
323 | 0.1
324 |
325 |
326 |
327 |
328 |
329 |
330 | true
331 | 20.0
332 | 0 0 0 0 0 0
333 | false
334 |
335 |
336 |
337 | 1
338 | 1
339 | 0
340 | 0
341 |
342 |
343 |
344 | 0.01
345 | 0.04
346 | 0.1
347 |
348 |
349 |
350 |
351 |
352 |
353 | true
354 | 20.0
355 | 0 0 0 0 0 0
356 | false
357 |
358 |
359 |
360 | 1
361 | 1
362 | 0
363 | 0
364 |
365 |
366 |
367 | 0.01
368 | 0.04
369 | 0.1
370 |
371 |
372 |
373 |
374 |
375 |
376 | true
377 | 20.0
378 | 0 0 0 0 0 0
379 | false
380 |
381 |
382 |
383 | 1
384 | 1
385 | 0
386 | 0
387 |
388 |
389 |
390 | 0.01
391 | 0.04
392 | 0.1
393 |
394 |
395 |
396 |
397 |
398 |
399 | true
400 | 30
401 | gyro_link
402 | imu/data
403 | imu/is_calibrated
404 | 2.89e-06
405 | 0 0 0
406 | 0 0 0
407 |
408 |
409 |
410 |
411 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_1.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_1_gazebo.urdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_1_gazebo.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_2.urdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 |
151 |
152 |
153 |
154 |
155 |
156 |
184 |
185 |
186 |
187 |
188 |
189 |
190 |
191 |
192 |
193 |
194 |
195 |
196 |
197 |
198 |
199 |
200 |
201 |
202 |
203 |
204 |
205 |
206 |
207 |
208 |
209 |
210 |
211 |
212 |
213 |
214 |
215 |
216 |
217 |
218 |
219 |
220 |
221 |
222 |
223 |
224 |
225 | true
226 | 40
227 | right_wheel_joint
228 | left_wheel_joint
229 | 0.235
230 | 0.072
231 | 1.0
232 |
233 | cmd_vel
234 | odom
235 | odom
236 | base_footprint
237 |
238 |
239 | true
240 | 100.0
241 | base_link
242 | simple_controller/absolute_position
243 | 0
244 | map
245 | 0 0 0
246 | 0 0 0
247 |
248 |
249 |
250 |
251 | 1.0
252 | 1.0
253 | 1000000.0
254 | 100.0
255 | 0.001
256 | 1.0
257 |
258 |
259 | 1.0
260 | 1.0
261 | 1000000.0
262 | 100.0
263 | 0.001
264 | 1.0
265 |
266 |
267 | 0.0
268 | 0.0
269 | 1000000.0
270 | 100.0
271 | 0.001
272 | 1.0
273 |
274 |
275 | 0.0
276 | 0.0
277 | 1000000.0
278 | 100.0
279 | 0.001
280 | 1.0
281 |
282 |
283 |
284 | true
285 | 20.0
286 | 0 0 0 0 0 0
287 | false
288 |
289 |
290 |
291 | 1
292 | 1
293 | 0
294 | 0
295 |
296 |
297 |
298 | 0.0160
299 | 0.04
300 | 0.1
301 |
302 |
303 |
304 |
305 |
306 |
307 | true
308 | 20.0
309 | 0 0 0 0 0 0
310 | false
311 |
312 |
313 |
314 | 1
315 | 1
316 | 0
317 | 0
318 |
319 |
320 |
321 | 0.01
322 | 0.04
323 | 0.1
324 |
325 |
326 |
327 |
328 |
329 |
330 | true
331 | 20.0
332 | 0 0 0 0 0 0
333 | false
334 |
335 |
336 |
337 | 1
338 | 1
339 | 0
340 | 0
341 |
342 |
343 |
344 | 0.01
345 | 0.04
346 | 0.1
347 |
348 |
349 |
350 |
351 |
352 |
353 | true
354 | 20.0
355 | 0 0 0 0 0 0
356 | false
357 |
358 |
359 |
360 | 1
361 | 1
362 | 0
363 | 0
364 |
365 |
366 |
367 | 0.01
368 | 0.04
369 | 0.1
370 |
371 |
372 |
373 |
374 |
375 |
376 | true
377 | 20.0
378 | 0 0 0 0 0 0
379 | false
380 |
381 |
382 |
383 | 1
384 | 1
385 | 0
386 | 0
387 |
388 |
389 |
390 | 0.01
391 | 0.04
392 | 0.1
393 |
394 |
395 |
396 |
397 |
398 |
399 | true
400 | 30
401 | gyro_link
402 | imu/data
403 | imu/is_calibrated
404 | 2.89e-06
405 | 0 0 0
406 | 0 0 0
407 |
408 |
409 |
410 |
411 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_2.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_2_gazebo.urdf:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_2_gazebo.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_base.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
29 |
30 |
31 |
32 |
33 |
34 |
35 |
36 |
37 |
38 |
39 |
40 |
41 |
42 |
43 |
44 |
45 |
46 |
47 |
48 |
49 |
50 |
51 |
52 |
53 |
54 |
55 |
56 |
57 |
58 |
59 |
60 |
61 |
62 |
63 |
64 |
65 |
66 |
67 |
68 |
69 |
70 |
71 |
72 |
73 |
74 |
75 |
76 |
77 |
78 |
79 |
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 |
88 |
89 |
90 |
91 |
92 |
93 |
94 |
95 |
96 |
97 |
98 |
99 |
100 |
101 |
102 |
103 |
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 |
114 |
115 |
116 |
117 |
118 |
119 |
120 |
121 |
122 |
123 |
124 |
125 |
126 |
127 |
128 |
129 |
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 |
138 |
139 |
140 |
141 |
142 |
143 |
144 |
145 |
146 |
147 |
148 |
149 |
150 |
151 |
152 |
153 |
154 |
155 |
156 |
157 |
185 |
186 |
187 |
188 |
189 |
190 |
191 |
192 |
193 |
194 |
195 |
196 |
197 |
198 |
199 |
200 |
201 |
202 |
203 |
204 |
205 |
206 |
207 |
208 |
209 |
210 |
211 |
212 |
213 |
214 |
215 |
216 |
217 |
218 |
219 |
220 |
221 |
222 |
223 |
224 |
225 |
226 |
227 |
228 |
229 |
230 |
231 |
232 |
233 |
234 |
235 |
236 |
237 |
--------------------------------------------------------------------------------
/ca_description/urdf/create_base_gazebo.urdf.xacro:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 | true
7 | ${diffdrive_update_rate}
8 | right_wheel_joint
9 | left_wheel_joint
10 | ${wheel_separation}
11 | ${wheel_radius * 2}
12 | ${wheel_torque}
13 |
14 | cmd_vel
15 | odom
16 | odom
17 | base_footprint
18 |
19 |
20 |
21 | true
22 | 100.0
23 | base_link
24 | simple_controller/absolute_position
25 | 0
26 | map
27 | 0 0 0
28 | 0 0 0
29 |
30 |
31 |
32 |
33 |
34 | 1.0
35 | 1.0
36 | 1000000.0
37 | 100.0
38 | 0.001
39 | 1.0
40 |
41 |
42 |
43 | 1.0
44 | 1.0
45 | 1000000.0
46 | 100.0
47 | 0.001
48 | 1.0
49 |
50 |
51 | 0.0
52 | 0.0
53 | 1000000.0
54 | 100.0
55 | 0.001
56 | 1.0
57 |
58 |
59 |
60 | 0.0
61 | 0.0
62 | 1000000.0
63 | 100.0
64 | 0.001
65 | 1.0
66 |
67 |
68 |
69 |
70 |
71 |
72 | true
73 | 30
74 | gyro_link
75 | imu/data
76 | imu/is_calibrated
77 | ${0.0017*0.0017}
78 | 0 0 0
79 | 0 0 0
80 |
81 |
82 |
83 |
84 |
85 |
86 |
87 | true
88 | 20.0
89 | 0 0 0 0 0 0
90 | false
91 |
92 |
93 |
94 | 1
95 | 1
96 | 0
97 | 0
98 |
99 |
100 |
101 | 0.0160
102 | 0.04
103 | 0.1
104 |
105 |
106 |
107 |
108 |
109 |
110 |
111 |
112 |
113 | true
114 | 20.0
115 | 0 0 0 0 0 0
116 | false
117 |
118 |
119 |
120 | 1
121 | 1
122 | 0
123 | 0
124 |
125 |
126 |
127 | 0.01
128 | 0.04
129 | 0.1
130 |
131 |
132 |
133 |
134 |
135 |
136 |
137 | true
138 | 20.0
139 | 0 0 0 0 0 0
140 | false
141 |
142 |
143 |
144 | 1
145 | 1
146 | 0
147 | 0
148 |
149 |
150 |
151 | 0.01
152 | 0.04
153 | 0.1
154 |
155 |
156 |
157 |
158 |
159 |
160 |
161 | true
162 | 20.0
163 | 0 0 0 0 0 0
164 | false
165 |
166 |
167 |
168 | 1
169 | 1
170 | 0
171 | 0
172 |
173 |
174 |
175 | 0.01
176 | 0.04
177 | 0.1
178 |
179 |
180 |
181 |
182 |
183 |
184 |
185 | true
186 | 20.0
187 | 0 0 0 0 0 0
188 | false
189 |
190 |
191 |
192 | 1
193 | 1
194 | 0
195 | 0
196 |
197 |
198 |
199 | 0.01
200 | 0.04
201 | 0.1
202 |
203 |
204 |
205 |
206 |
207 |
208 |
--------------------------------------------------------------------------------
/ca_driver/CHANGELOG.rst:
--------------------------------------------------------------------------------
1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2 | Changelog for package create_driver
3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4 |
5 | 1.3.0 (2018-06-10)
6 | ------------------
7 | * Add explicit dependency on catkin_EXPORTED_TARGETS
8 | * This ensures ca_msgs is built before ca_driver.
9 | * Migrate to package.xml format 2
10 | * Minor linting to package files.
11 | * Add roslint test and fix lint issues
12 | * find_package libcreate instead of downloading as external project
13 | * Add support for defining and playing songs
14 | * Update install rules
15 | * Refactor launch files and expose robot base and odometry frame IDs as parameters
16 | * Refactor CMakeLists.txt and package.xml files and add missing install rules
17 | * Contributors: Clyde McQueen, Jacob Perron
18 |
19 | 1.2.0 (2016-10-07)
20 | ------------------
21 | * Add support for more than two robot models and fix compiling with latest changes from libcreate.
22 | * Contributors: Ben Wolsieffer
23 |
24 | 1.1.0 (2016-07-23)
25 | ------------------
26 | * Add diagnostics (Battery, Safety, Serial, Mode, Driver)
27 | * Refactor URDF to support differences between Create 1 and 2, while using a common base.
28 | * Include a mesh for the Create 1, borrowed from turtlebot_create.
29 | * Update launch files to support Create 1.
30 | * Publish JointState messages for the wheels.
31 | * Contributors: Ben Wolsieffer, Jacob Perron
32 |
33 | 1.0.1 (2016-05-24)
34 | ------------------
35 | * Get pose covariance from underlying library
36 | * Make publishing TF (odom frame) optional
37 | * Add launch file argument making description optional
38 | * Update libcreate tag, with odometry patch
39 | * Add git as build dependency
40 | * Move ChargingState publisher with other battery state information
41 | * Add Bumper message with contact sensor states and light sensor states
42 | * Add header to all custom message types
43 | * Contributors: Jacob Perron
44 |
45 | 1.0.0 (2016-04-01)
46 | ------------------
47 | * Update libcreate git tag
48 | * Rename variables according to ROS cpp style guide
49 | * Run clang-format
50 | * Fix typo
51 | * Add ca_description as runtime dependency to ca_driver
52 | * Change message type of various battery info topics
53 | * Add ChargingState and Mode messages
54 | * Add charging state and mode publishers
55 | * Add 'ca_msgs' package
56 | * Update ca_driver README.md
57 | * Rename 'create_driver' and 'create_tools' to 'ca_driver' and 'ca_tools'
58 | * Contributors: Jacob Perron
59 |
60 | 0.4.0 (2016-03-26)
61 | ------------------
62 | * Add timestamp to odometry message
63 | * Update libcreate tag (with odometry fix)
64 | * Fix sign error for battery current and temperature
65 | * Update tag for libcreate
66 | * Add delay before starting dock demo in case of Create 1
67 | * Compute and publish battery charge ratio
68 | * Add README.md for create_driver
69 | * Add support for Create 1
70 | * Contributors: Jacob Perron
71 |
72 | 0.3.0 (2016-03-17)
73 | ------------------
74 | * Add dock / undock support
75 | * Publish characters received by omni directional IR sensor
76 | * Add battery info support
77 | * Contributors: Jacob Perron
78 |
79 | 0.2.0 (2016-03-03)
80 | ------------------
81 | * Add covariances to odometry messages
82 | * Add set 7Seg display with ASCII
83 | * Add LED support
84 | * Add publishers for button presses
85 | * Contributors: Jacob Perron
86 |
87 | 0.1.0 (2016-02-05)
88 | ------------------
89 | * Fixed bugs: Private nodehandle now gets params, added missing timestamp to tf messages
90 | * Added tf broadcaster for odom frame
91 | * Added CI (travis)
92 | * Now publishing velocities in odom messages
93 | * Added anti-latch mechanism
94 | * Switch to using node handle with private namespace for parameters only
95 | * Velocity commands now accepted in m/s
96 | * Updated launch file
97 | * Initial commit
98 | * Contributors: Jacob Perron
99 |
--------------------------------------------------------------------------------
/ca_driver/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project(ca_driver)
3 |
4 | if(NOT CMAKE_CXX_STANDARD)
5 | set(CMAKE_CXX_STANDARD 14)
6 | endif()
7 |
8 | find_package(ament_cmake REQUIRED)
9 | find_package(ca_msgs REQUIRED)
10 | find_package(diagnostic_msgs REQUIRED)
11 | # find_package(diagnostic_updater REQUIRED)
12 | find_package(geometry_msgs REQUIRED)
13 | find_package(libcreate REQUIRED)
14 | find_package(nav_msgs REQUIRED)
15 | find_package(rclcpp REQUIRED)
16 | find_package(rclcpp_lifecycle REQUIRED)
17 | find_package(sensor_msgs REQUIRED)
18 | find_package(std_msgs REQUIRED)
19 | find_package(tf2 REQUIRED)
20 | find_package(tf2_ros REQUIRED)
21 |
22 | include_directories(
23 | include
24 | ${ca_msgs_INCLUDE_DIRS}
25 | ${diagnostic_msgs_INCLUDE_DIRS}
26 | # ${diagnostic_updater_INCLUDE_DIRS}
27 | ${geometry_msgs_INCLUDE_DIRS}
28 | ${libcreate_INCLUDE_DIRS}
29 | ${nav_msgs_INCLUDE_DIRS}
30 | ${rclcpp_INCLUDE_DIRS}
31 | ${sensor_msgs_INCLUDE_DIRS}
32 | ${std_msgs_INCLUDE_DIRS}
33 | ${tf2_INCLUDE_DIRS}
34 | )
35 |
36 | add_executable(${PROJECT_NAME} src/create_driver.cpp)
37 | ament_target_dependencies(${PROJECT_NAME}
38 | "ca_msgs"
39 | "diagnostic_msgs"
40 | # "diagnostic_updater"
41 | "geometry_msgs"
42 | "libcreate"
43 | "nav_msgs"
44 | "rclcpp"
45 | "rclcpp_lifecycle"
46 | "sensor_msgs"
47 | "std_msgs"
48 | "tf2"
49 | "tf2_ros"
50 | )
51 |
52 | if(BUILD_TESTING)
53 | find_package(ament_lint_auto REQUIRED)
54 | ament_lint_auto_find_test_dependencies()
55 | endif()
56 |
57 | install(TARGETS ${PROJECT_NAME}
58 | DESTINATION lib/${PROJECT_NAME}
59 | )
60 |
61 | install(DIRECTORY include/${PROJECT_NAME}
62 | DESTINATION include/${PROJECT_NAME}
63 | FILES_MATCHING PATTERN "*.h"
64 | )
65 |
66 | install(DIRECTORY config
67 | DESTINATION config
68 | )
69 |
70 | ament_package()
71 |
--------------------------------------------------------------------------------
/ca_driver/README.md:
--------------------------------------------------------------------------------
1 | # ca_driver
2 |
3 | ROS driver for iRobot's Create 1 and 2.
4 |
--------------------------------------------------------------------------------
/ca_driver/config/default.yaml:
--------------------------------------------------------------------------------
1 | # The device path for the robot
2 | dev: "/dev/ttyUSB0"
3 |
4 | # Baud rate. Passing this parameter overwrites the inferred value based on the robot_model
5 | # baud: 115200
6 |
7 | # Base frame ID
8 | base_frame: "base_footprint"
9 |
10 | # Odometry frame ID
11 | odom_frame: "odom"
12 |
13 | # Time (s) without receiving a velocity command before stopping the robot
14 | latch_cmd_duration: 0.2
15 |
16 | # Internal loop update rate (Hz)
17 | loop_hz: 10.0
18 |
19 | # Whether to publish the transform between odom_frame and base_frame
20 | publish_tf: true
21 |
--------------------------------------------------------------------------------
/ca_driver/include/create_driver/create_driver.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2015 Jacob Perron (Autonomy Lab, Simon Fraser University)
2 |
3 | #ifndef CREATE_DRIVER__CREATE_DRIVER_HPP_
4 | #define CREATE_DRIVER__CREATE_DRIVER_HPP_
5 |
6 | #include
7 |
8 | #include
9 | #include
10 | #include
11 | #include
12 | #include
13 | #include
14 | #include
15 | #include
16 | #include
17 | #include
18 | #include
19 | #include
20 | #include
21 | #include
22 | #include
23 | #include
24 | #include
25 |
26 | #include "ca_msgs/msg/bumper.hpp"
27 | #include "ca_msgs/msg/charging_state.hpp"
28 | #include "ca_msgs/msg/define_song.hpp"
29 | #include "ca_msgs/msg/mode.hpp"
30 | #include "ca_msgs/msg/play_song.hpp"
31 | #include "create/create.h"
32 |
33 | namespace create_autonomy
34 | {
35 | static const double MAX_DBL = std::numeric_limits::max();
36 | static const double COVARIANCE[36] = {
37 | 1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5, 1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5,
38 | 0.0, 0.0, MAX_DBL, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, MAX_DBL, 0.0, 0.0,
39 | 0.0, 0.0, 0.0, 0.0, MAX_DBL, 0.0, 1e-5, 1e-5, 0.0, 0.0, 0.0, 1e-5};
40 |
41 | class CreateDriver : public rclcpp_lifecycle::LifecycleNode
42 | {
43 | private:
44 | std::unique_ptr robot_;
45 | create::RobotModel model_;
46 | rclcpp::TimerBase::SharedPtr timer_;
47 | std::shared_ptr tf_broadcaster_;
48 | ca_msgs::msg::Mode mode_msg_;
49 | ca_msgs::msg::ChargingState charging_state_msg_;
50 | ca_msgs::msg::Bumper bumper_msg_;
51 | nav_msgs::msg::Odometry odom_msg_;
52 | geometry_msgs::msg::TransformStamped tf_odom_;
53 | rclcpp::Clock ros_clock_;
54 | rclcpp::Time last_cmd_vel_time_;
55 | std_msgs::msg::Empty empty_msg_;
56 | std_msgs::msg::Float32 float32_msg_;
57 | std_msgs::msg::UInt16 uint16_msg_;
58 | std_msgs::msg::Int16 int16_msg_;
59 | sensor_msgs::msg::JointState joint_state_msg_;
60 |
61 | // ROS params
62 | std::string dev_;
63 | std::string base_frame_;
64 | std::string odom_frame_;
65 | double latch_duration_;
66 | double loop_hz_;
67 | bool publish_tf_;
68 | int64_t baud_;
69 |
70 | void cmdVelCallback(const geometry_msgs::msg::Twist::UniquePtr msg);
71 | void debrisLEDCallback(const std_msgs::msg::Bool::UniquePtr msg);
72 | void spotLEDCallback(const std_msgs::msg::Bool::UniquePtr msg);
73 | void dockLEDCallback(const std_msgs::msg::Bool::UniquePtr msg);
74 | void checkLEDCallback(const std_msgs::msg::Bool::UniquePtr msg);
75 | void powerLEDCallback(const std_msgs::msg::UInt8MultiArray::UniquePtr msg);
76 | void setASCIICallback(const std_msgs::msg::UInt8MultiArray::UniquePtr msg);
77 | void dockCallback(const std_msgs::msg::Empty::UniquePtr msg);
78 | void undockCallback(const std_msgs::msg::Empty::UniquePtr msg);
79 | void defineSongCallback(const ca_msgs::msg::DefineSong::UniquePtr msg);
80 | void playSongCallback(const ca_msgs::msg::PlaySong::UniquePtr msg);
81 |
82 | void update();
83 | void publishOdom();
84 | void publishJointState();
85 | void publishBatteryInfo();
86 | void publishButtonPresses() const;
87 | void publishOmniChar();
88 | void publishMode();
89 | void publishBumperInfo();
90 | void publishWheeldrop();
91 |
92 | protected:
93 | rclcpp::Subscription::SharedPtr cmd_vel_sub_;
94 | rclcpp::Subscription::SharedPtr debris_led_sub_;
95 | rclcpp::Subscription::SharedPtr spot_led_sub_;
96 | rclcpp::Subscription::SharedPtr dock_led_sub_;
97 | rclcpp::Subscription::SharedPtr check_led_sub_;
98 | rclcpp::Subscription::SharedPtr power_led_sub_;
99 | rclcpp::Subscription::SharedPtr set_ascii_sub_;
100 | rclcpp::Subscription::SharedPtr dock_sub_;
101 | rclcpp::Subscription::SharedPtr undock_sub_;
102 | rclcpp::Subscription::SharedPtr define_song_sub_;
103 | rclcpp::Subscription::SharedPtr play_song_sub_;
104 |
105 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr odom_pub_;
106 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr clean_btn_pub_;
107 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr day_btn_pub_;
108 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr hour_btn_pub_;
109 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr min_btn_pub_;
110 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr dock_btn_pub_;
111 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr spot_btn_pub_;
112 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr voltage_pub_;
113 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr current_pub_;
114 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr charge_pub_;
115 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr charge_ratio_pub_;
116 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr capacity_pub_;
117 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr temperature_pub_;
118 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr charging_state_pub_;
119 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr omni_char_pub_;
120 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr mode_pub_;
121 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr bumper_pub_;
122 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr wheeldrop_pub_;
123 | rclcpp_lifecycle::LifecyclePublisher::SharedPtr wheel_joint_pub_;
124 |
125 | public:
126 | explicit CreateDriver(const std::string & name);
127 | ~CreateDriver();
128 |
129 | using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
130 |
131 | CallbackReturn on_configure(const rclcpp_lifecycle::State &);
132 | CallbackReturn on_activate(const rclcpp_lifecycle::State &);
133 | CallbackReturn on_deactivate(const rclcpp_lifecycle::State &);
134 | CallbackReturn on_cleanup(const rclcpp_lifecycle::State &);
135 | };
136 |
137 | } // namespace create_autonomy
138 |
139 | #endif // CREATE_DRIVER__CREATE_DRIVER_HPP_
140 |
--------------------------------------------------------------------------------
/ca_driver/launch/create_1.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/ca_driver/launch/create_2.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/ca_driver/launch/roomba_400.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/ca_driver/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | ca_driver
4 | 2.0.0
5 | ROS 2 driver for iRobot's Create and Roomba platforms, based on libcreate
6 |
7 | Jacob Perron
8 | Yutaka Kondo
9 |
10 | BSD
11 |
12 | http://wiki.ros.org/ca_driver
13 |
14 | Jacob Perron
15 |
16 | ament_cmake
17 |
18 | ca_msgs
19 | diagnostic_msgs
20 |
21 | geometry_msgs
22 | libcreate
23 | nav_msgs
24 | rclcpp
25 | rclcpp_lifecycle
26 | sensor_msgs
27 | std_msgs
28 | tf2
29 | tf2_ros
30 |
31 | ca_description
32 |
33 | ament_lint_auto
34 | ament_lint_common
35 |
36 |
37 | ament_cmake
38 |
39 |
40 |
--------------------------------------------------------------------------------
/ca_driver/src/create_driver.cpp:
--------------------------------------------------------------------------------
1 | // Copyright 2015 Jacob Perron (Autonomy Lab, Simon Fraser University)
2 |
3 | #include "create_driver/create_driver.hpp"
4 |
5 | #include
6 | #include
7 |
8 | #include
9 | #include
10 | #include
11 |
12 | namespace create_autonomy
13 | {
14 | using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
15 |
16 | CreateDriver::CreateDriver(const std::string & name)
17 | : LifecycleNode(name),
18 | model_(create::RobotModel::CREATE_2),
19 | ros_clock_(RCL_ROS_TIME),
20 | last_cmd_vel_time_(ros_clock_.now()),
21 | dev_("/dev/ttyUSB0"),
22 | base_frame_("base_footprint"),
23 | odom_frame_("odom"),
24 | latch_duration_(0.2),
25 | loop_hz_(10.0),
26 | publish_tf_(true)
27 | {
28 | std::string robot_model_name = "CREATE_2";
29 |
30 | declare_parameter("dev", dev_);
31 | declare_parameter("robot_model", robot_model_name);
32 | declare_parameter("base_frame", base_frame_);
33 | declare_parameter("odom_frame", odom_frame_);
34 | declare_parameter("latch_cmd_duration", latch_duration_);
35 | declare_parameter("loop_hz", loop_hz_);
36 | declare_parameter("publish_tf", publish_tf_);
37 |
38 | get_parameter("dev", dev_);
39 | get_parameter("robot_model", robot_model_name);
40 | get_parameter("base_frame", base_frame_);
41 | get_parameter("odom_frame", odom_frame_);
42 | get_parameter("latch_cmd_duration", latch_duration_);
43 | get_parameter("loop_hz", loop_hz_);
44 | get_parameter("publish_tf", publish_tf_);
45 |
46 | if (robot_model_name == "ROOMBA_400") {
47 | model_ = create::RobotModel::ROOMBA_400;
48 | } else if (robot_model_name == "CREATE_1") {
49 | model_ = create::RobotModel::CREATE_1;
50 | } else if (robot_model_name == "CREATE_2") {
51 | model_ = create::RobotModel::CREATE_2;
52 | } else {
53 | RCLCPP_FATAL(
54 | get_logger(), "[CREATE] Robot model \"%s\" is not known.", robot_model_name.c_str());
55 | rclcpp::shutdown();
56 | return;
57 | }
58 |
59 | RCLCPP_INFO(get_logger(), "[CREATE] \"%s\" selected", robot_model_name.c_str());
60 |
61 | baud_ = model_.getBaud();
62 | declare_parameter("baud", baud_);
63 | get_parameter("baud", baud_);
64 | }
65 |
66 | CreateDriver::~CreateDriver() {}
67 |
68 | CallbackReturn CreateDriver::on_configure(const rclcpp_lifecycle::State &)
69 | {
70 | using namespace std::chrono_literals;
71 |
72 | robot_ = std::make_unique(model_);
73 |
74 | // Set frame_id's
75 | mode_msg_.header.frame_id = base_frame_;
76 | bumper_msg_.header.frame_id = base_frame_;
77 | charging_state_msg_.header.frame_id = base_frame_;
78 | tf_odom_.header.frame_id = odom_frame_;
79 | tf_odom_.child_frame_id = base_frame_;
80 | odom_msg_.header.frame_id = odom_frame_;
81 | odom_msg_.child_frame_id = base_frame_;
82 | joint_state_msg_.name.resize(2);
83 | joint_state_msg_.position.resize(2);
84 | joint_state_msg_.velocity.resize(2);
85 | joint_state_msg_.effort.resize(2);
86 | joint_state_msg_.name[0] = "left_wheel_joint";
87 | joint_state_msg_.name[1] = "right_wheel_joint";
88 |
89 | // Populate initial covariances
90 | for (int i = 0; i < 36; i++) {
91 | odom_msg_.pose.covariance[i] = COVARIANCE[i];
92 | odom_msg_.twist.covariance[i] = COVARIANCE[i];
93 | }
94 |
95 | // Setup subscribers
96 | cmd_vel_sub_ = create_subscription(
97 | "cmd_vel", 10, std::bind(&CreateDriver::cmdVelCallback, this, std::placeholders::_1));
98 | debris_led_sub_ = create_subscription(
99 | "debris_led", 10, std::bind(&CreateDriver::debrisLEDCallback, this, std::placeholders::_1));
100 | spot_led_sub_ = create_subscription(
101 | "spot_led", 10, std::bind(&CreateDriver::spotLEDCallback, this, std::placeholders::_1));
102 | dock_led_sub_ = create_subscription(
103 | "dock_led", 10, std::bind(&CreateDriver::dockLEDCallback, this, std::placeholders::_1));
104 | check_led_sub_ = create_subscription(
105 | "check_led", 10, std::bind(&CreateDriver::checkLEDCallback, this, std::placeholders::_1));
106 | power_led_sub_ = create_subscription(
107 | "power_led", 10, std::bind(&CreateDriver::powerLEDCallback, this, std::placeholders::_1));
108 | set_ascii_sub_ = create_subscription(
109 | "set_ascii", 10, std::bind(&CreateDriver::setASCIICallback, this, std::placeholders::_1));
110 | dock_sub_ = create_subscription(
111 | "dock", 10, std::bind(&CreateDriver::dockCallback, this, std::placeholders::_1));
112 | undock_sub_ = create_subscription(
113 | "undock", 10, std::bind(&CreateDriver::undockCallback, this, std::placeholders::_1));
114 | define_song_sub_ = create_subscription(
115 | "define_song", 10, std::bind(&CreateDriver::defineSongCallback, this, std::placeholders::_1));
116 | play_song_sub_ = create_subscription(
117 | "play_song", 10, std::bind(&CreateDriver::playSongCallback, this, std::placeholders::_1));
118 |
119 | // Setup publishers
120 | odom_pub_ = create_publisher("odom", 10);
121 | clean_btn_pub_ = create_publisher("clean_button", 10);
122 | day_btn_pub_ = create_publisher("day_button", 10);
123 | hour_btn_pub_ = create_publisher("hour_button", 10);
124 | min_btn_pub_ = create_publisher("minute_button", 10);
125 | dock_btn_pub_ = create_publisher("dock_button", 10);
126 | spot_btn_pub_ = create_publisher("spot_button", 10);
127 | voltage_pub_ = create_publisher("battery/voltage", 10);
128 | current_pub_ = create_publisher("battery/current", 10);
129 | charge_pub_ = create_publisher("battery/charge", 10);
130 | charge_ratio_pub_ = create_publisher("battery/charge_ratio", 10);
131 | capacity_pub_ = create_publisher("battery/capacity", 10);
132 | temperature_pub_ = create_publisher("battery/temperature", 10);
133 | charging_state_pub_ = create_publisher("battery/charging_state", 10);
134 | omni_char_pub_ = create_publisher("ir_omni", 10);
135 | mode_pub_ = create_publisher("mode", 10);
136 | bumper_pub_ = create_publisher("bumper", 10);
137 | wheeldrop_pub_ = create_publisher("wheeldrop", 10);
138 | wheel_joint_pub_ = create_publisher("joint_states", 10);
139 |
140 | tf_broadcaster_ = std::make_shared(shared_from_this());
141 | timer_ = create_wall_timer(100ms, std::bind(&CreateDriver::update, this));
142 | timer_->cancel();
143 |
144 | RCLCPP_INFO(get_logger(), "[CREATE] Ready.");
145 |
146 | return CallbackReturn::SUCCESS;
147 | }
148 |
149 | CallbackReturn CreateDriver::on_activate(const rclcpp_lifecycle::State &)
150 | {
151 | if (!robot_->connect(dev_, baud_)) {
152 | RCLCPP_FATAL(get_logger(), "[CREATE] Failed to establish serial connection with Create.");
153 | rclcpp::shutdown();
154 | }
155 |
156 | RCLCPP_INFO(get_logger(), "[CREATE] Connection established.");
157 |
158 | // Start in full control mode
159 | robot_->setMode(create::MODE_FULL);
160 |
161 | // Show robot's battery level
162 | RCLCPP_INFO(
163 | get_logger(), "[CREATE] Battery level %.2f %%",
164 | (robot_->getBatteryCharge() / robot_->getBatteryCapacity()) * 100.0);
165 |
166 | odom_pub_->on_activate();
167 | clean_btn_pub_->on_activate();
168 | day_btn_pub_->on_activate();
169 | hour_btn_pub_->on_activate();
170 | min_btn_pub_->on_activate();
171 | dock_btn_pub_->on_activate();
172 | spot_btn_pub_->on_activate();
173 | voltage_pub_->on_activate();
174 | current_pub_->on_activate();
175 | charge_pub_->on_activate();
176 | charge_ratio_pub_->on_activate();
177 | capacity_pub_->on_activate();
178 | temperature_pub_->on_activate();
179 | charging_state_pub_->on_activate();
180 | omni_char_pub_->on_activate();
181 | mode_pub_->on_activate();
182 | bumper_pub_->on_activate();
183 | wheeldrop_pub_->on_activate();
184 | wheel_joint_pub_->on_activate();
185 |
186 | timer_->reset();
187 |
188 | return CallbackReturn::SUCCESS;
189 | }
190 |
191 | CallbackReturn CreateDriver::on_deactivate(const rclcpp_lifecycle::State &)
192 | {
193 | timer_->cancel();
194 |
195 | odom_pub_->on_deactivate();
196 | clean_btn_pub_->on_deactivate();
197 | day_btn_pub_->on_deactivate();
198 | hour_btn_pub_->on_deactivate();
199 | min_btn_pub_->on_deactivate();
200 | dock_btn_pub_->on_deactivate();
201 | spot_btn_pub_->on_deactivate();
202 | voltage_pub_->on_deactivate();
203 | current_pub_->on_deactivate();
204 | charge_pub_->on_deactivate();
205 | charge_ratio_pub_->on_deactivate();
206 | capacity_pub_->on_deactivate();
207 | temperature_pub_->on_deactivate();
208 | charging_state_pub_->on_deactivate();
209 | omni_char_pub_->on_deactivate();
210 | mode_pub_->on_deactivate();
211 | bumper_pub_->on_deactivate();
212 | wheeldrop_pub_->on_deactivate();
213 | wheel_joint_pub_->on_deactivate();
214 |
215 | robot_->disconnect();
216 | RCLCPP_INFO(get_logger(), "[CREATE] Connection terminated.");
217 |
218 | return CallbackReturn::SUCCESS;
219 | }
220 |
221 | CallbackReturn CreateDriver::on_cleanup(const rclcpp_lifecycle::State &)
222 | {
223 | timer_.reset();
224 |
225 | odom_pub_.reset();
226 | clean_btn_pub_.reset();
227 | day_btn_pub_.reset();
228 | hour_btn_pub_.reset();
229 | min_btn_pub_.reset();
230 | dock_btn_pub_.reset();
231 | spot_btn_pub_.reset();
232 | voltage_pub_.reset();
233 | current_pub_.reset();
234 | charge_pub_.reset();
235 | charge_ratio_pub_.reset();
236 | capacity_pub_.reset();
237 | temperature_pub_.reset();
238 | charging_state_pub_.reset();
239 | omni_char_pub_.reset();
240 | mode_pub_.reset();
241 | bumper_pub_.reset();
242 | wheeldrop_pub_.reset();
243 | wheel_joint_pub_.reset();
244 |
245 | cmd_vel_sub_.reset();
246 | debris_led_sub_.reset();
247 | spot_led_sub_.reset();
248 | dock_led_sub_.reset();
249 | check_led_sub_.reset();
250 | power_led_sub_.reset();
251 | set_ascii_sub_.reset();
252 | dock_sub_.reset();
253 | undock_sub_.reset();
254 | define_song_sub_.reset();
255 | play_song_sub_.reset();
256 |
257 | robot_.reset();
258 |
259 | return CallbackReturn::SUCCESS;
260 | }
261 |
262 | void CreateDriver::cmdVelCallback(const geometry_msgs::msg::Twist::UniquePtr msg)
263 | {
264 | robot_->drive(msg->linear.x, msg->angular.z);
265 | last_cmd_vel_time_ = ros_clock_.now();
266 | }
267 |
268 | void CreateDriver::debrisLEDCallback(const std_msgs::msg::Bool::UniquePtr msg)
269 | {
270 | robot_->enableDebrisLED(msg->data);
271 | }
272 |
273 | void CreateDriver::spotLEDCallback(const std_msgs::msg::Bool::UniquePtr msg)
274 | {
275 | robot_->enableSpotLED(msg->data);
276 | }
277 |
278 | void CreateDriver::dockLEDCallback(const std_msgs::msg::Bool::UniquePtr msg)
279 | {
280 | robot_->enableDockLED(msg->data);
281 | }
282 |
283 | void CreateDriver::checkLEDCallback(const std_msgs::msg::Bool::UniquePtr msg)
284 | {
285 | robot_->enableCheckRobotLED(msg->data);
286 | }
287 |
288 | void CreateDriver::powerLEDCallback(const std_msgs::msg::UInt8MultiArray::UniquePtr msg)
289 | {
290 | if (msg->data.empty()) {
291 | RCLCPP_ERROR(get_logger(), "[CREATE] No values provided to set power LED");
292 | } else {
293 | if (msg->data.size() < 2) {
294 | robot_->setPowerLED(msg->data[0]);
295 | } else {
296 | robot_->setPowerLED(msg->data[0], msg->data[1]);
297 | }
298 | }
299 | }
300 |
301 | void CreateDriver::setASCIICallback(const std_msgs::msg::UInt8MultiArray::UniquePtr msg)
302 | {
303 | bool result = false;
304 | if (msg->data.empty()) {
305 | RCLCPP_ERROR(get_logger(), "[CREATE] No ASCII digits provided");
306 | } else if (msg->data.size() < 2) {
307 | result = robot_->setDigitsASCII(msg->data[0], ' ', ' ', ' ');
308 | } else if (msg->data.size() < 3) {
309 | result = robot_->setDigitsASCII(msg->data[0], msg->data[1], ' ', ' ');
310 | } else if (msg->data.size() < 4) {
311 | result = robot_->setDigitsASCII(msg->data[0], msg->data[1], msg->data[2], ' ');
312 | } else {
313 | result = robot_->setDigitsASCII(msg->data[0], msg->data[1], msg->data[2], msg->data[3]);
314 | }
315 |
316 | if (!result) {
317 | RCLCPP_ERROR(get_logger(), "[CREATE] ASCII character out of range [32, 126]");
318 | }
319 | }
320 |
321 | void CreateDriver::dockCallback(const std_msgs::msg::Empty::UniquePtr msg)
322 | {
323 | robot_->setMode(create::MODE_PASSIVE);
324 |
325 | if (model_.getVersion() <= create::V_2) {
326 | usleep(1000000); // Create 1 requires a delay (1 sec)
327 | }
328 |
329 | // Call docking behaviour
330 | robot_->dock();
331 | }
332 |
333 | void CreateDriver::undockCallback(const std_msgs::msg::Empty::UniquePtr msg)
334 | {
335 | // Switch robot back to FULL mode
336 | robot_->setMode(create::MODE_FULL);
337 | }
338 |
339 | void CreateDriver::defineSongCallback(const ca_msgs::msg::DefineSong::UniquePtr msg)
340 | {
341 | if (!robot_->defineSong(
342 | msg->song, msg->length, &(msg->notes.front()), &(msg->durations.front()))) {
343 | RCLCPP_ERROR(
344 | get_logger(), "[CREATE] Failed to define song %d of length %d", msg->song, msg->length);
345 | }
346 | }
347 |
348 | void CreateDriver::playSongCallback(const ca_msgs::msg::PlaySong::UniquePtr msg)
349 | {
350 | if (!robot_->playSong(msg->song)) {
351 | RCLCPP_ERROR(get_logger(), "[CREATE] Failed to play song %d", msg->song);
352 | }
353 | }
354 |
355 | void CreateDriver::update()
356 | {
357 | publishOdom();
358 | publishJointState();
359 | publishBatteryInfo();
360 | publishButtonPresses();
361 | publishOmniChar();
362 | publishMode();
363 | publishBumperInfo();
364 | publishWheeldrop();
365 |
366 | // If last velocity command was sent longer than latch duration, stop robot
367 | if (ros_clock_.now() - last_cmd_vel_time_ >= rclcpp::Duration(latch_duration_)) {
368 | robot_->drive(0, 0);
369 | }
370 | }
371 |
372 | void CreateDriver::publishOdom()
373 | {
374 | create::Pose pose = robot_->getPose();
375 | create::Vel vel = robot_->getVel();
376 |
377 | // Populate position info
378 | tf2::Quaternion quat;
379 | quat.setRPY(0, 0, pose.yaw);
380 | odom_msg_.header.stamp = ros_clock_.now();
381 | odom_msg_.pose.pose.position.x = pose.x;
382 | odom_msg_.pose.pose.position.y = pose.y;
383 | odom_msg_.pose.pose.orientation.x = quat.x();
384 | odom_msg_.pose.pose.orientation.y = quat.y();
385 | odom_msg_.pose.pose.orientation.z = quat.z();
386 | odom_msg_.pose.pose.orientation.w = quat.w();
387 |
388 | // Populate velocity info
389 | odom_msg_.twist.twist.linear.x = vel.x;
390 | odom_msg_.twist.twist.linear.y = vel.y;
391 | odom_msg_.twist.twist.angular.z = vel.yaw;
392 |
393 | // Update covariances
394 | odom_msg_.pose.covariance[0] = static_cast(pose.covariance[0]);
395 | odom_msg_.pose.covariance[1] = pose.covariance[1];
396 | odom_msg_.pose.covariance[5] = pose.covariance[2];
397 | odom_msg_.pose.covariance[6] = pose.covariance[3];
398 | odom_msg_.pose.covariance[7] = pose.covariance[4];
399 | odom_msg_.pose.covariance[11] = pose.covariance[5];
400 | odom_msg_.pose.covariance[30] = pose.covariance[6];
401 | odom_msg_.pose.covariance[31] = pose.covariance[7];
402 | odom_msg_.pose.covariance[35] = pose.covariance[8];
403 | odom_msg_.twist.covariance[0] = vel.covariance[0];
404 | odom_msg_.twist.covariance[1] = vel.covariance[1];
405 | odom_msg_.twist.covariance[5] = vel.covariance[2];
406 | odom_msg_.twist.covariance[6] = vel.covariance[3];
407 | odom_msg_.twist.covariance[7] = vel.covariance[4];
408 | odom_msg_.twist.covariance[11] = vel.covariance[5];
409 | odom_msg_.twist.covariance[30] = vel.covariance[6];
410 | odom_msg_.twist.covariance[31] = vel.covariance[7];
411 | odom_msg_.twist.covariance[35] = vel.covariance[8];
412 |
413 | if (publish_tf_) {
414 | tf_odom_.header.stamp = ros_clock_.now();
415 | tf_odom_.transform.translation.x = pose.x;
416 | tf_odom_.transform.translation.y = pose.y;
417 | tf_odom_.transform.rotation.x = quat.x();
418 | tf_odom_.transform.rotation.y = quat.y();
419 | tf_odom_.transform.rotation.z = quat.z();
420 | tf_odom_.transform.rotation.w = quat.w();
421 | tf_broadcaster_->sendTransform(tf_odom_);
422 | }
423 |
424 | odom_pub_->publish(odom_msg_);
425 | }
426 |
427 | void CreateDriver::publishJointState()
428 | {
429 | // Publish joint states
430 | double wheelRadius = model_.getWheelDiameter() / 2.0;
431 |
432 | joint_state_msg_.header.stamp = ros_clock_.now();
433 | joint_state_msg_.position[0] = robot_->getLeftWheelDistance() / wheelRadius;
434 | joint_state_msg_.position[1] = robot_->getRightWheelDistance() / wheelRadius;
435 | joint_state_msg_.velocity[0] = robot_->getRequestedLeftWheelVel() / wheelRadius;
436 | joint_state_msg_.velocity[1] = robot_->getRequestedRightWheelVel() / wheelRadius;
437 | wheel_joint_pub_->publish(joint_state_msg_);
438 | }
439 |
440 | void CreateDriver::publishBatteryInfo()
441 | {
442 | float32_msg_.data = robot_->getVoltage();
443 | voltage_pub_->publish(float32_msg_);
444 | float32_msg_.data = robot_->getCurrent();
445 | current_pub_->publish(float32_msg_);
446 | float32_msg_.data = robot_->getBatteryCharge();
447 | charge_pub_->publish(float32_msg_);
448 | float32_msg_.data = robot_->getBatteryCapacity();
449 | capacity_pub_->publish(float32_msg_);
450 | int16_msg_.data = robot_->getTemperature();
451 | temperature_pub_->publish(int16_msg_);
452 | float32_msg_.data = robot_->getBatteryCharge() / robot_->getBatteryCapacity();
453 | charge_ratio_pub_->publish(float32_msg_);
454 |
455 | const create::ChargingState charging_state = robot_->getChargingState();
456 | charging_state_msg_.header.stamp = ros_clock_.now();
457 | switch (charging_state) {
458 | case create::CHARGE_NONE:
459 | charging_state_msg_.state = ca_msgs::msg::ChargingState::CHARGE_NONE;
460 | break;
461 | case create::CHARGE_RECONDITION:
462 | charging_state_msg_.state = ca_msgs::msg::ChargingState::CHARGE_RECONDITION;
463 | break;
464 |
465 | case create::CHARGE_FULL:
466 | charging_state_msg_.state = ca_msgs::msg::ChargingState::CHARGE_FULL;
467 | break;
468 |
469 | case create::CHARGE_TRICKLE:
470 | charging_state_msg_.state = ca_msgs::msg::ChargingState::CHARGE_TRICKLE;
471 | break;
472 |
473 | case create::CHARGE_WAITING:
474 | charging_state_msg_.state = ca_msgs::msg::ChargingState::CHARGE_WAITING;
475 | break;
476 |
477 | case create::CHARGE_FAULT:
478 | charging_state_msg_.state = ca_msgs::msg::ChargingState::CHARGE_FAULT;
479 | break;
480 | }
481 | charging_state_pub_->publish(charging_state_msg_);
482 | }
483 |
484 | void CreateDriver::publishButtonPresses() const
485 | {
486 | if (robot_->isCleanButtonPressed()) {
487 | clean_btn_pub_->publish(empty_msg_);
488 | }
489 | if (robot_->isDayButtonPressed()) {
490 | day_btn_pub_->publish(empty_msg_);
491 | }
492 | if (robot_->isHourButtonPressed()) {
493 | hour_btn_pub_->publish(empty_msg_);
494 | }
495 | if (robot_->isMinButtonPressed()) {
496 | min_btn_pub_->publish(empty_msg_);
497 | }
498 | if (robot_->isDockButtonPressed()) {
499 | dock_btn_pub_->publish(empty_msg_);
500 | }
501 | if (robot_->isSpotButtonPressed()) {
502 | spot_btn_pub_->publish(empty_msg_);
503 | }
504 | }
505 |
506 | void CreateDriver::publishOmniChar()
507 | {
508 | uint8_t ir_char = robot_->getIROmni();
509 | uint16_msg_.data = ir_char;
510 | omni_char_pub_->publish(uint16_msg_);
511 | // TODO(jacobperron): Publish info based on character, such as dock in sight
512 | }
513 |
514 | void CreateDriver::publishMode()
515 | {
516 | const create::CreateMode mode = robot_->getMode();
517 | mode_msg_.header.stamp = ros_clock_.now();
518 | switch (mode) {
519 | case create::MODE_OFF:
520 | mode_msg_.mode = mode_msg_.MODE_OFF;
521 | break;
522 | case create::MODE_PASSIVE:
523 | mode_msg_.mode = mode_msg_.MODE_PASSIVE;
524 | break;
525 | case create::MODE_SAFE:
526 | mode_msg_.mode = mode_msg_.MODE_SAFE;
527 | break;
528 | case create::MODE_FULL:
529 | mode_msg_.mode = mode_msg_.MODE_FULL;
530 | break;
531 | default:
532 | mode_msg_.mode = mode_msg_.MODE_UNKNOWN;
533 | break;
534 | }
535 | mode_pub_->publish(mode_msg_);
536 | }
537 |
538 | void CreateDriver::publishBumperInfo()
539 | {
540 | bumper_msg_.header.stamp = ros_clock_.now();
541 | bumper_msg_.is_left_pressed = robot_->isLeftBumper();
542 | bumper_msg_.is_right_pressed = robot_->isRightBumper();
543 |
544 | if (model_.getVersion() >= create::V_3) {
545 | bumper_msg_.is_light_left = robot_->isLightBumperLeft();
546 | bumper_msg_.is_light_front_left = robot_->isLightBumperFrontLeft();
547 | bumper_msg_.is_light_center_left = robot_->isLightBumperCenterLeft();
548 | bumper_msg_.is_light_right = robot_->isLightBumperRight();
549 | bumper_msg_.is_light_front_right = robot_->isLightBumperFrontRight();
550 | bumper_msg_.is_light_center_right = robot_->isLightBumperCenterRight();
551 |
552 | bumper_msg_.light_signal_left = robot_->getLightSignalLeft();
553 | bumper_msg_.light_signal_front_left = robot_->getLightSignalFrontLeft();
554 | bumper_msg_.light_signal_center_left = robot_->getLightSignalCenterLeft();
555 | bumper_msg_.light_signal_right = robot_->getLightSignalRight();
556 | bumper_msg_.light_signal_front_right = robot_->getLightSignalFrontRight();
557 | bumper_msg_.light_signal_center_right = robot_->getLightSignalCenterRight();
558 | }
559 |
560 | bumper_pub_->publish(bumper_msg_);
561 | }
562 |
563 | void CreateDriver::publishWheeldrop()
564 | {
565 | if (robot_->isWheeldrop()) {
566 | wheeldrop_pub_->publish(empty_msg_);
567 | }
568 | }
569 |
570 | } // namespace create_autonomy
571 |
572 | int main(int argc, char ** argv)
573 | {
574 | setvbuf(stdout, NULL, _IONBF, BUFSIZ);
575 | rclcpp::init(argc, argv);
576 |
577 | rclcpp::executors::SingleThreadedExecutor executor;
578 | auto node = std::make_shared("ca_driver");
579 | executor.add_node(node->get_node_base_interface());
580 | executor.spin();
581 | rclcpp::shutdown();
582 |
583 | return 0;
584 | }
585 |
--------------------------------------------------------------------------------
/ca_msgs/CHANGELOG.rst:
--------------------------------------------------------------------------------
1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2 | Changelog for package ca_msgs
3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4 |
5 | 1.3.0 (2018-06-10)
6 | ------------------
7 | * Migrate to package.xml format 2
8 | * Minor linting to package files.
9 | * Add support for defining and playing songs
10 | * Refactor CMakeLists.txt and package.xml files and add missing install rules
11 | * Contributors: Clyde McQueen, Jacob Perron
12 |
13 | 1.2.0 (2016-10-07)
14 | ------------------
15 |
16 | 1.1.0 (2016-07-23)
17 | ------------------
18 |
19 | 1.0.1 (2016-05-24)
20 | ------------------
21 | * Add Bumper message with contact sensor states and light sensor states
22 | * Add header to all custom message types
23 | * Contributors: Jacob Perron
24 |
25 | 1.0.0 (2016-04-01)
26 | ------------------
27 | * Add ChargingState and Mode messages
28 | * Add charging state and mode publishers
29 | * Add 'ca_msgs' package
30 | * Contributors: Jacob Perron
31 |
--------------------------------------------------------------------------------
/ca_msgs/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project(ca_msgs)
3 |
4 | if(NOT CMAKE_CXX_STANDARD)
5 | set(CMAKE_CXX_STANDARD 14)
6 | endif()
7 |
8 | find_package(ament_cmake REQUIRED)
9 | find_package(rosidl_default_generators REQUIRED)
10 | find_package(std_msgs REQUIRED)
11 | find_package(common_interfaces REQUIRED)
12 |
13 | rosidl_generate_interfaces(${PROJECT_NAME}
14 | "msg/Bumper.msg"
15 | "msg/ChargingState.msg"
16 | "msg/DefineSong.msg"
17 | "msg/Mode.msg"
18 | "msg/PlaySong.msg"
19 | DEPENDENCIES std_msgs
20 | )
21 |
22 | ament_export_dependencies(rosidl_default_runtime)
23 | ament_package()
24 |
--------------------------------------------------------------------------------
/ca_msgs/msg/Bumper.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header
2 |
3 | # Contact sensors
4 | bool is_left_pressed
5 | bool is_right_pressed
6 |
7 | # Bumper light sensors (Create 2 only) in order from left to right
8 | # Value = true if an obstacle detected
9 | bool is_light_left
10 | bool is_light_front_left
11 | bool is_light_center_left
12 | bool is_light_center_right
13 | bool is_light_front_right
14 | bool is_light_right
15 |
16 | # Raw light sensor signals
17 | # Values in range [0, 4095]
18 | uint16 light_signal_left
19 | uint16 light_signal_front_left
20 | uint16 light_signal_center_left
21 | uint16 light_signal_center_right
22 | uint16 light_signal_front_right
23 | uint16 light_signal_right
24 |
--------------------------------------------------------------------------------
/ca_msgs/msg/ChargingState.msg:
--------------------------------------------------------------------------------
1 | uint8 CHARGE_NONE=0
2 | uint8 CHARGE_RECONDITION=1
3 | uint8 CHARGE_FULL=2
4 | uint8 CHARGE_TRICKLE=3
5 | uint8 CHARGE_WAITING=4
6 | uint8 CHARGE_FAULT=5
7 |
8 | std_msgs/Header header
9 | uint8 state
10 |
--------------------------------------------------------------------------------
/ca_msgs/msg/DefineSong.msg:
--------------------------------------------------------------------------------
1 | uint8 song # song number [0-3]
2 | uint8 length # song length [1-16]
3 | uint8[] notes # notes defined by the MIDI note numbering scheme. Notes outside the range of [31-127] are rest notes.
4 | float32[] durations # durations in seconds. Maximum duration is 255/64.
5 |
--------------------------------------------------------------------------------
/ca_msgs/msg/Mode.msg:
--------------------------------------------------------------------------------
1 | uint8 MODE_OFF=0
2 | uint8 MODE_PASSIVE=1
3 | uint8 MODE_SAFE=2
4 | uint8 MODE_FULL=3
5 | uint8 MODE_UNKNOWN=255
6 |
7 | std_msgs/Header header
8 | uint8 mode
9 |
--------------------------------------------------------------------------------
/ca_msgs/msg/PlaySong.msg:
--------------------------------------------------------------------------------
1 | uint8 song # song number [0-3]
2 |
--------------------------------------------------------------------------------
/ca_msgs/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | ca_msgs
4 | 2.0.0
5 | Common message definitions for create_autonomy
6 |
7 | Jacob Perron
8 | Yutaka Kondo
9 |
10 | BSD
11 |
12 | http://wiki.ros.org/ca_msgs
13 |
14 | Jacob Perron
15 |
16 | ament_cmake
17 | rosidl_default_generators
18 |
19 | std_msgs
20 | common_interfaces
21 | rosidl_default_runtime
22 | rosidl_interface_packages
23 |
24 |
25 | ament_cmake
26 |
27 |
28 |
--------------------------------------------------------------------------------
/ca_tools/CHANGELOG.rst:
--------------------------------------------------------------------------------
1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2 | Changelog for package create_tools
3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4 |
5 | 1.3.0 (2018-06-10)
6 | ------------------
7 | * Migrate to package.xml format 2
8 | * Minor linting to package files.
9 | * Update install rules
10 | * Refactor launch files and expose robot base and odometry frame IDs as parameters
11 | * Refactor CMakeLists.txt and package.xml files and add missing install rules
12 | * Contributors: Jacob Perron
13 |
14 | 1.2.0 (2016-10-07)
15 | ------------------
16 |
17 | 1.1.0 (2016-07-23)
18 | ------------------
19 |
20 | 1.0.1 (2016-05-24)
21 | ------------------
22 |
23 | 1.0.0 (2016-04-01)
24 | ------------------
25 | * Fix typo in joy_teleop.launch
26 | * Rename 'create_driver' and 'create_tools' to 'ca_driver' and 'ca_tools'
27 | * Contributors: Jacob Perron
28 |
29 | 0.4.0 (2016-03-26)
30 | ------------------
31 | * Update teleop configurations files
32 | * Add configuration file for Logitech F710 controller
33 | * Contributors: Jacob Perron
34 |
35 | 0.3.0 (2016-03-17)
36 | ------------------
37 |
38 | 0.2.0 (2016-03-03)
39 | ------------------
40 |
41 | 0.1.0 (2016-02-05)
42 | ------------------
43 | * Updated create_tools package
44 | * Switch to using node handle with private namespace for parameters only
45 | * Added create_tools with teleop launch and config files
46 | * Contributors: Jacob Perron
47 |
--------------------------------------------------------------------------------
/ca_tools/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project(ca_tools)
3 |
4 | if(NOT CMAKE_CXX_STANDARD)
5 | set(CMAKE_CXX_STANDARD 14)
6 | endif()
7 |
8 | find_package(ament_cmake REQUIRED)
9 | find_package(joy REQUIRED)
10 | find_package(teleop_twist_joy REQUIRED)
11 |
12 | install(DIRECTORY config
13 | DESTINATION config
14 | )
15 |
16 | ament_package()
17 |
--------------------------------------------------------------------------------
/ca_tools/config/log710.yaml:
--------------------------------------------------------------------------------
1 | # Logitech F710 wireless controller
2 | # Deadman (enable) button: Right Trigger
3 | # D<>X button (located on the back panel) must be set to D
4 | teleop:
5 | piloting:
6 | type: topic
7 | message_type: "geometry_msgs/Twist"
8 | topic_name: cmd_vel
9 | deadman_buttons: [7]
10 | axis_mappings:
11 | -
12 | axis: 3 # Right thumb stick (up/down)
13 | target: linear.x
14 | scale: 0.4
15 | offset: 0.0
16 | -
17 | axis: 2 # Right thumb stick (left/right)
18 | target: angular.z
19 | scale: 2.5
20 | offset: 0.0
21 | dock:
22 | type: topic
23 | message_type: "std_msgs/Empty"
24 | topic_name: dock
25 | deadman_buttons: [3, 7] # RT + Y
26 | axis_mappings: []
27 | undock:
28 | type: topic
29 | message_type: "std_msgs/Empty"
30 | topic_name: undock
31 | deadman_buttons: [1, 7] # RT + A
32 | axis_mappings: []
33 |
--------------------------------------------------------------------------------
/ca_tools/config/xbox360.yaml:
--------------------------------------------------------------------------------
1 | # XBox 360 wired controller
2 | teleop:
3 | piloting:
4 | type: topic
5 | message_type: "geometry_msgs/Twist"
6 | topic_name: cmd_vel
7 | deadman_buttons: [] # No deadman buttons
8 | axis_mappings:
9 | -
10 | axis: 4 # Right thumb (up/down)
11 | target: linear.x
12 | scale: 0.4
13 | offset: 0.0
14 | -
15 | axis: 3 # Right thumb stick (left/right)
16 | target: angular.z
17 | scale: 2.5
18 | offset: 0.0
19 |
--------------------------------------------------------------------------------
/ca_tools/launch/joy_teleop.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
--------------------------------------------------------------------------------
/ca_tools/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | ca_tools
4 | 2.0.0
5 | Launch and configuration files for common accessories when working with Create/Roomba platforms.
6 |
7 | Jacob Perron
8 | Yutaka Kondo
9 |
10 | BSD
11 |
12 | http://wiki.ros.org/ca_tools
13 |
14 | Jacob Perron
15 |
16 | ament_cmake
17 |
18 | joy
19 | teleop_twist_joy
20 |
21 |
22 | ament_cmake
23 |
24 |
25 |
--------------------------------------------------------------------------------
/create_autonomy/CHANGELOG.rst:
--------------------------------------------------------------------------------
1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
2 | Changelog for package create_autonomy
3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
4 |
5 | 1.3.0 (2018-06-10)
6 | ------------------
7 | * Migrate to package.xml format 2
8 | * Minor linting to package files.
9 | * Contributors: Jacob Perron
10 |
11 | 1.2.0 (2016-10-07)
12 | ------------------
13 |
14 | 1.1.0 (2016-07-23)
15 | ------------------
16 |
17 | 1.0.1 (2016-05-24)
18 | ------------------
19 |
20 | 1.0.0 (2016-04-01)
21 | ------------------
22 | * Add ca_description package
23 | * Add ca_msgs to metapackage
24 | * Rename 'create_driver' and 'create_tools' to 'ca_driver' and 'ca_tools'
25 | * Contributors: Jacob Perron
26 |
27 | 0.4.0 (2016-03-26)
28 | ------------------
29 |
30 | 0.3.0 (2016-03-17)
31 | ------------------
32 |
33 | 0.2.0 (2016-03-03)
34 | ------------------
35 |
36 | 0.1.0 (2016-02-05)
37 | ------------------
38 | * Added CI (travis)
39 | * Added create_tools with teleop launch and config files
40 | * Initial commit
41 | * Contributors: Jacob Perron
42 |
--------------------------------------------------------------------------------
/create_autonomy/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project(create_autonomy)
3 |
4 | if(NOT CMAKE_CXX_STANDARD)
5 | set(CMAKE_CXX_STANDARD 14)
6 | endif()
7 |
8 | find_package(ament_cmake REQUIRED)
9 | # find_package(ca_description EQUIRED)
10 | # find_package(ca_driver REQUIRED)
11 | find_package(ca_msgs REQUIRED)
12 | # find_package(ca_tools REQUIRED)
13 |
14 | ament_package()
15 |
--------------------------------------------------------------------------------
/create_autonomy/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 | create_autonomy
4 | 2.0.0
5 | ROS 2 driver for iRobot's Create 1 and 2, based on the libcreate C++ library
6 |
7 | Jacob Perron
8 | Yutaka Kondo
9 |
10 | BSD
11 |
12 | http://wiki.ros.org/create_autonomy
13 | http://github.com/AutonomyLab/create_autonomy
14 |
15 | Jacob Perron
16 |
17 | ament_cmake
18 |
19 | ca_description
20 | ca_driver
21 | ca_msgs
22 | ca_tools
23 |
24 |
25 | ament_cmake
26 |
27 |
28 |
--------------------------------------------------------------------------------