瀏覽代碼

ros2 driver initial commit

main
Marcus Grieger 1 年之前
父節點
當前提交
b49e66784f
共有 35 個文件被更改,包括 496 次插入0 次删除
  1. +17
    -0
      ros2_hexapod/src/hexapod/servo/LICENSE
  2. +20
    -0
      ros2_hexapod/src/hexapod/servo/package.xml
  3. +0
    -0
      ros2_hexapod/src/hexapod/servo/resource/servo
  4. +0
    -0
      ros2_hexapod/src/hexapod/servo/servo/__init__.py
  5. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/c1.json
  6. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/c2.json
  7. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/c3.json
  8. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/c4.json
  9. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/c5.json
  10. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/c6.json
  11. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/f1.json
  12. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/f2.json
  13. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/f3.json
  14. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/f4.json
  15. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/f5.json
  16. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/f6.json
  17. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/t1.json
  18. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/t2.json
  19. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/t3.json
  20. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/t4.json
  21. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/t5.json
  22. +5
    -0
      ros2_hexapod/src/hexapod/servo/servo/calibration/t6.json
  23. +9
    -0
      ros2_hexapod/src/hexapod/servo/servo/servo_calibration.py
  24. +79
    -0
      ros2_hexapod/src/hexapod/servo/servo/servo_mapping.json
  25. +11
    -0
      ros2_hexapod/src/hexapod/servo/servo/servo_mapping.py
  26. +93
    -0
      ros2_hexapod/src/hexapod/servo/servo/servo_node.py
  27. +4
    -0
      ros2_hexapod/src/hexapod/servo/setup.cfg
  28. +26
    -0
      ros2_hexapod/src/hexapod/servo/setup.py
  29. +25
    -0
      ros2_hexapod/src/hexapod/servo/test/test_copyright.py
  30. +25
    -0
      ros2_hexapod/src/hexapod/servo/test/test_flake8.py
  31. +23
    -0
      ros2_hexapod/src/hexapod/servo/test/test_pep257.py
  32. +32
    -0
      ros2_hexapod/src/hexapod/servo_interface/CMakeLists.txt
  33. +17
    -0
      ros2_hexapod/src/hexapod/servo_interface/LICENSE
  34. +3
    -0
      ros2_hexapod/src/hexapod/servo_interface/msg/SetServo.msg
  35. +22
    -0
      ros2_hexapod/src/hexapod/servo_interface/package.xml

+ 17
- 0
ros2_hexapod/src/hexapod/servo/LICENSE 查看文件

@@ -0,0 +1,17 @@
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.

+ 20
- 0
ros2_hexapod/src/hexapod/servo/package.xml 查看文件

@@ -0,0 +1,20 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>servo</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="marcus@grieger.xyz">wuselfuzz</maintainer>
<license>MIT</license>

<depend>servo_interface</depend>

<test_depend>ament_copyright</test_depend>
<test_depend>ament_flake8</test_depend>
<test_depend>ament_pep257</test_depend>
<test_depend>python3-pytest</test_depend>

<export>
<build_type>ament_python</build_type>
</export>
</package>

+ 0
- 0
ros2_hexapod/src/hexapod/servo/resource/servo 查看文件


+ 0
- 0
ros2_hexapod/src/hexapod/servo/servo/__init__.py 查看文件


+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/c1.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 591.0714285714287,
"slope": 11.178571428571427
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/c2.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 572.1428571428573,
"slope": 11.595238095238093
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/c3.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 558.2142857142858,
"slope": 11.511904761904761
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/c4.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 641.0714285714287,
"slope": 11.845238095238093
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/c5.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 578.2142857142858,
"slope": 11.511904761904761
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/c6.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 521.0714285714287,
"slope": 11.845238095238093
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/f1.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 701.4285714285713,
"slope": 10.952380952380953
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/f2.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 609.6428571428572,
"slope": 10.892857142857142
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/f3.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 620.3571428571429,
"slope": 11.202380952380953
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/f4.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 746.7857142857143,
"slope": 10.892857142857142
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/f5.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 705.0000000000002,
"slope": 10.928571428571427
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/f6.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 600.0,
"slope": 10.904761904761903
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/t1.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 607.4999999999999,
"slope": 10.964285714285715
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/t2.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 682.1428571428572,
"slope": 11.071428571428571
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/t3.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 806.0714285714287,
"slope": 11.25
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/t4.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 769.6428571428571,
"slope": 10.797619047619047
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/t5.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 593.9285714285716,
"slope": 10.94047619047619
}

+ 5
- 0
ros2_hexapod/src/hexapod/servo/servo/calibration/t6.json 查看文件

@@ -0,0 +1,5 @@
{
"description": "",
"intercept": 740.7142857142857,
"slope": 11.214285714285715
}

+ 9
- 0
ros2_hexapod/src/hexapod/servo/servo/servo_calibration.py 查看文件

@@ -0,0 +1,9 @@
import pkgutil
import json

import servo.servo_mapping

servo_calibration = {}
for label in servo.servo_mapping.servo_mapping:
calibration_data = pkgutil.get_data(__name__, f"calibration/{label}.json")
servo_calibration[label] = json.loads(calibration_data)

+ 79
- 0
ros2_hexapod/src/hexapod/servo/servo/servo_mapping.json 查看文件

@@ -0,0 +1,79 @@
{
"t1": {
"address": 64,
"channel": 15
},
"f1": {
"address": 64,
"channel": 14
},
"c1": {
"address": 64,
"channel": 13
},

"t2": {
"address": 64,
"channel": 11
},
"f2": {
"address": 64,
"channel": 10
},
"c2": {
"address": 64,
"channel": 9
},
"t3": {
"address": 64,
"channel": 0
},
"f3": {
"address": 64,
"channel": 1
},
"c3": {
"address": 64,
"channel": 2
},
"t4": {
"address": 65,
"channel": 15
},
"f4": {
"address": 65,
"channel": 14
},
"c4": {
"address": 65,
"channel": 13
},
"t5": {
"address": 65,
"channel": 4
},
"f5": {
"address": 65,
"channel": 5
},
"c5": {
"address": 65,
"channel": 6
},

"t6": {
"address": 65,
"channel": 0
},
"f6": {
"address": 65,
"channel": 1
},
"c6": {
"address": 65,
"channel": 2
}
}

+ 11
- 0
ros2_hexapod/src/hexapod/servo/servo/servo_mapping.py 查看文件

@@ -0,0 +1,11 @@
import pkgutil
import json


#servo_mapping_filename = "/home/wuselfuzz/hexapod_ng/configuration/servo_mapping.json"

#with open(servo_mapping_filename, "r") as f:
# servo_mapping = json.load(f)

servo_mapping_data = pkgutil.get_data(__name__, "servo_mapping.json")
servo_mapping = json.loads(servo_mapping_data)

+ 93
- 0
ros2_hexapod/src/hexapod/servo/servo/servo_node.py 查看文件

@@ -0,0 +1,93 @@
import rclpy
import rclpy.node

import servo_interface.msg

import servo.servo_mapping
import servo.servo_calibration

import board
import busio
import adafruit_pca9685


class ServoNode(rclpy.node.Node):
def __init__(self):
super().__init__('servo_node')
self.subscription = self.create_subscription(
servo_interface.msg.SetServo,
'set_servo',
self.listener_callback,
10
)
self.i2c = busio.I2C(board.SCL, board.SDA)
self.pca9685 = {}
self.pwm = {}
for label in servo.servo_mapping.servo_mapping:
m = servo.servo_mapping.servo_mapping[label]
address = m['address']
channel = m['channel']
if address not in self.pca9685:
self.get_logger().info(f'Creating PCA9685 object for i2c address {address}')
self.pca9685[address] = adafruit_pca9685.PCA9685(self.i2c, address=address)
self.pca9685[address].frequency = 50

self.get_logger().debug(f'Adding {address}:{channel} as {label}')
self.pwm[label] = self.pca9685[address].channels[channel]

self.calibration = servo.servo_calibration.servo_calibration
self.get_logger().debug(f'Calibration for {label}: {self.calibration[label]}')
def listener_callback(self, msg):
self.get_logger().info(f'label: {msg.label} powered: {msg.powered} angle: {msg.angle}')
if msg.label not in self.pwm:
self.get_logger().warn(f'no pwm channel associated to {msg.label}')
return

label = msg.label
powered = msg.powered
angle = msg.angle

pwm_channel = self.pwm[label]
calibration = servo.servo_calibration.servo_calibration[label]
if angle < 0:
self.get_logger().warn(f'angle must be between 0 and 180: {angle}, forcing 0')
angle = 0
if angle > 180:
self.get_logger().warn(f'angle must be between 0 and 180: {angle}, forcing 180')
angle = 180
usec = calibration['intercept'] + angle * calibration['slope']
self.get_logger().info(f'usec: {usec}')
duty_cycle = int(usec * (0xffff / 20000))
self.get_logger().info(f'duty_cycle: {duty_cycle}')
if powered:
pwm_channel.duty_cycle = duty_cycle
else:
pwm_channel.duty_cycle = 0

def main(args=None):
rclpy.init(args=args)
servo_node = ServoNode()
rclpy.spin(servo_node)
servo_node.destroy_node()
rclpy.shutdown()


if __name__ == '__main__':
main()

+ 4
- 0
ros2_hexapod/src/hexapod/servo/setup.cfg 查看文件

@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/servo
[install]
install_scripts=$base/lib/servo

+ 26
- 0
ros2_hexapod/src/hexapod/servo/setup.py 查看文件

@@ -0,0 +1,26 @@
from setuptools import find_packages, setup

package_name = 'servo'

setup(
name=package_name,
version='0.0.0',
packages=find_packages(exclude=['test']),
data_files=[
('share/ament_index/resource_index/packages',
['resource/' + package_name]),
('share/' + package_name, ['package.xml']),
],
install_requires=['setuptools'],
zip_safe=True,
maintainer='wuselfuzz',
maintainer_email='marcus@grieger.xyz',
description='TODO: Package description',
license='MIT',
tests_require=['pytest'],
entry_points={
'console_scripts': [
'servo_node = servo.servo_node:main'
],
},
)

+ 25
- 0
ros2_hexapod/src/hexapod/servo/test/test_copyright.py 查看文件

@@ -0,0 +1,25 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# 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.

from ament_copyright.main import main
import pytest


# Remove the `skip` decorator once the source file(s) have a copyright header
@pytest.mark.skip(reason='No copyright header has been placed in the generated source file.')
@pytest.mark.copyright
@pytest.mark.linter
def test_copyright():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found errors'

+ 25
- 0
ros2_hexapod/src/hexapod/servo/test/test_flake8.py 查看文件

@@ -0,0 +1,25 @@
# Copyright 2017 Open Source Robotics Foundation, Inc.
#
# 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.

from ament_flake8.main import main_with_errors
import pytest


@pytest.mark.flake8
@pytest.mark.linter
def test_flake8():
rc, errors = main_with_errors(argv=[])
assert rc == 0, \
'Found %d code style errors / warnings:\n' % len(errors) + \
'\n'.join(errors)

+ 23
- 0
ros2_hexapod/src/hexapod/servo/test/test_pep257.py 查看文件

@@ -0,0 +1,23 @@
# Copyright 2015 Open Source Robotics Foundation, Inc.
#
# 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.

from ament_pep257.main import main
import pytest


@pytest.mark.linter
@pytest.mark.pep257
def test_pep257():
rc = main(argv=['.', 'test'])
assert rc == 0, 'Found code style errors / warnings'

+ 32
- 0
ros2_hexapod/src/hexapod/servo_interface/CMakeLists.txt 查看文件

@@ -0,0 +1,32 @@
cmake_minimum_required(VERSION 3.8)
project(servo_interface)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
# uncomment the following section in order to fill in
# further dependencies manually.
# find_package(<dependency> REQUIRED)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()

find_package(rosidl_default_generators REQUIRED)

rosidl_generate_interfaces(${PROJECT_NAME}
"msg/SetServo.msg"
)

ament_package()

+ 17
- 0
ros2_hexapod/src/hexapod/servo_interface/LICENSE 查看文件

@@ -0,0 +1,17 @@
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:

The above copyright notice and this permission notice shall be included in
all copies or substantial portions of the Software.

THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL
THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
THE SOFTWARE.

+ 3
- 0
ros2_hexapod/src/hexapod/servo_interface/msg/SetServo.msg 查看文件

@@ -0,0 +1,3 @@
string label
bool powered
float64 angle

+ 22
- 0
ros2_hexapod/src/hexapod/servo_interface/package.xml 查看文件

@@ -0,0 +1,22 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>servo_interface</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="marcus@grieger.xyz">wuselfuzz</maintainer>
<license>MIT</license>

<buildtool_depend>ament_cmake</buildtool_depend>

<buildtool_depend>rosidl_default_generators</buildtool_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
<member_of_group>rosidl_interface_packages</member_of_group>

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>

Loading…
取消
儲存