Skip to content

Commit

Permalink
Merge pull request #2 from tinymovr/develop
Browse files Browse the repository at this point in the history
Finalize Tinymovr ROS ahead of release
  • Loading branch information
yconst authored Sep 20, 2023
2 parents 71a74c7 + 7541a50 commit 9425279
Show file tree
Hide file tree
Showing 58 changed files with 2,647 additions and 649 deletions.
16 changes: 16 additions & 0 deletions .github/workflows/industrial_ci.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
name: CI

on: [push, pull_request]

jobs:
industrial_ci:
strategy:
matrix:
env:
- {ROS_DISTRO: noetic, ROS_REPO: main}
- {ROS_DISTRO: melodic, ROS_REPO: main}
runs-on: ubuntu-latest
steps:
- uses: actions/checkout@v3
- uses: 'ros-industrial/industrial_ci@master'
env: ${{matrix.env}}
34 changes: 22 additions & 12 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@ find_package(catkin REQUIRED COMPONENTS
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
INCLUDE_DIRS include include/tinymovr
LIBRARIES tinymovr_ros
CATKIN_DEPENDS controller_interface controller_manager roscpp rospy std_msgs sensor_msgs
# DEPENDS system_lib
Expand All @@ -123,16 +123,32 @@ catkin_package(
## Your package locations should be listed before other locations
include_directories(
include
include/tinymovr
${catkin_INCLUDE_DIRS}
)

set(TINYMOVR_SOURCES
src/tinymovr/can.cpp
src/tinymovr/comms.cpp
src/tinymovr/controller.cpp
src/tinymovr/current.cpp
src/tinymovr/encoder.cpp
src/tinymovr/motor.cpp
src/tinymovr/position.cpp
src/tinymovr/scheduler.cpp
src/tinymovr/tinymovr.cpp
src/tinymovr/traj_planner.cpp
src/tinymovr/velocity.cpp
src/tinymovr/voltage.cpp
src/tinymovr/watchdog.cpp
)

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

add_library(${PROJECT_NAME}_hw_iface src/socketcan_cpp.cpp src/tinymovr_can.cpp src/tm_hw_iface.cpp)
add_library(${PROJECT_NAME}_diffbot_hw_iface src/socketcan_cpp.cpp src/tinymovr_can.cpp src/diffbot_hw_iface.cpp)
add_library(${PROJECT_NAME}_joint_iface ${TINYMOVR_SOURCES} src/socketcan_cpp/socketcan_cpp.cpp src/tm_joint_iface.cpp)

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
Expand All @@ -142,8 +158,7 @@ add_library(${PROJECT_NAME}_diffbot_hw_iface src/socketcan_cpp.cpp src/tinymovr_
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
add_executable(${PROJECT_NAME}_node src/tm_hw_iface_node.cpp)
add_executable(${PROJECT_NAME}_diffbot_node src/diffbot_hw_iface_node.cpp)
add_executable(tinymovr_joint_iface_node src/tm_joint_iface_node.cpp)

## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
Expand All @@ -156,13 +171,8 @@ add_executable(${PROJECT_NAME}_diffbot_node src/diffbot_hw_iface_node.cpp)
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

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

target_link_libraries(${PROJECT_NAME}_diffbot_node
${PROJECT_NAME}_diffbot_hw_iface
target_link_libraries(tinymovr_joint_iface_node
${PROJECT_NAME}_joint_iface
${catkin_LIBRARIES}
)

Expand Down
76 changes: 72 additions & 4 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,8 +1,76 @@
__Tinymovr ROS Hardware Interface__

https://catkin-tools.readthedocs.io/en/latest/installing.html
A ROS package that provides hardware interfacing for Tinymovr devices. This interface allows for seamless integration of Tinymovr devices with ROS-based robotic systems, offering joint state and control through ROS topics and services.

https://www.howtoinstall.me/ubuntu/18-04/liburdfdom-headers-dev/
## Features
- Real-time reading of joint positions, velocities, and efforts.
- Ability to send joint command setpoints.
- Error handling and robust exception management.
- Compatible with standard ROS controllers, enabling a plug-and-play experience.

https://github.com/siposcsaba89/socketcan-cpp
## Prerequisites

https://stackoverflow.com/questions/17808084/fatal-error-libudev-h-no-such-file-or-directory
- ROS (Robot Operating System) - Tested with ROS Noetic, but should be compatible with other versions.
- SocketCAN tools and utilities installed.
- Tinymovr devices properly set up and calibrated.

## Installation

1. Navigate to your catkin workspace's source folder:

```bash
cd ~/catkin_ws/src/
```

2. Clone the repository:

```bash
git clone git@github.com:tinymovr/Tinymovr-ROS.git
```

3. Build your catkin workspace:

```bash
cd ~/catkin_ws/
catkin_make
```

4. Source the workspace:

```bash
source devel/setup.bash
```

## Run the Diffbot demo!

1. Ensure your Tinymovr instances are calibrated and well tuned, test functioning using Tinymovr Studio or CLI.

2. Configure your hardware in `config/hardware.yaml` and diff drive config in `config/diff_drive_config.yaml`

3. Start the `tinymovr_diffbot_demo_node` node:

```bash
roslaunch tinymovr_ros tinymovr_diffbot_demo_node.launch
```

4. Spin up a keyboard teleop and drive your robot:

```bash
rosrun teleop_twist_keyboard teleop_twist_keyboard.py cmd_vel:=/diff_drive_controller/cmd_vel
```

## Configuration

To customize the behavior of the Tinymovr ROS, adjust the parameters in the `config` directory. Here, you can set specifics about each joint, including joint names, IDs, and other parameters relevant to your hardware setup.

## API Documentation

Further details about the API and individual functions can be found in the generated Doxygen documentation. Please refer to the documentation for advanced use cases.

## Contributing

Contributions to improve and expand the functionality of Tinymovr ROS are welcome! Please open an issue or submit a pull request on the GitHub repository.

## License

This package is licensed under the [MIT License](LICENSE).
11 changes: 11 additions & 0 deletions avlos_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@

# All paths relative to this config file

generators:
generator_cpp:
enabled: true
paths:
output_helpers: ./include/tinymovr/helpers.hpp
output_header: ./include/tinymovr/tinymovr.hpp
output_impl: ./src/tinymovr/tinymovr.cpp

10 changes: 10 additions & 0 deletions config/diff_drive_config.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
diff_drive_controller:
type: "diff_drive_controller/DiffDriveController"
left_wheel: "wheel_1"
right_wheel: "wheel_2"
pose_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
twist_covariance_diagonal: [0.001, 0.001, 1000000.0, 1000000.0, 1000000.0, 1000.0]
publish_rate: 50.0
wheel_separation: 0.4
wheel_radius: 0.12
cmd_vel_timeout: 0.5
Empty file removed config/diffbot_hw_iface.yaml
Empty file.
19 changes: 19 additions & 0 deletions config/hardware.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
tinymovr_joint_iface:
joints:
wheel_2:
# hardware ID of the actuator
id: 2
offset: 3.14159265359 # in rad
delay_us: 200
#max-speed: 4.0 # in rad/s
rads_to_ticks: 14.323944878 # how many ticks in a rad
command_interface: velocity
wheel_1:
# hardware ID of the actuator
id: 1
offset: 3.14159265359 # in rad
delay_us: 200
#max-speed: 4.0 # in rad/s
rads_to_ticks: 14.323944878 # how many ticks in a rad
command_interface: velocity

Empty file removed config/tm_hw_iface.yaml
Empty file.
2 changes: 1 addition & 1 deletion include/socketcan_cpp/socketcan_cpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,4 +60,4 @@ namespace scpp
std::string m_interface;
SocketMode m_socket_mode;
};
}
}
24 changes: 24 additions & 0 deletions include/tinymovr/can.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
/*
* This file was automatically generated using Avlos.
* https://github.com/tinymovr/avlos
*
* Any changes to this file will be overwritten when
* content is regenerated.
*/

#pragma once

#include <helpers.hpp>

class Can_ : Node
{
public:

Can_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value):
Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {};
uint32_t get_rate(void);
void set_rate(uint32_t value);
uint32_t get_id(void);
void set_id(uint32_t value);

};
23 changes: 23 additions & 0 deletions include/tinymovr/comms.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
/*
* This file was automatically generated using Avlos.
* https://github.com/tinymovr/avlos
*
* Any changes to this file will be overwritten when
* content is regenerated.
*/

#pragma once

#include <helpers.hpp>
#include <can.hpp>

class Comms_ : Node
{
public:

Comms_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value):
Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value)
, can(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {};
Can_ can;

};
44 changes: 44 additions & 0 deletions include/tinymovr/controller.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
/*
* This file was automatically generated using Avlos.
* https://github.com/tinymovr/avlos
*
* Any changes to this file will be overwritten when
* content is regenerated.
*/

#pragma once

#include <helpers.hpp>
#include <position.hpp>
#include <velocity.hpp>
#include <current.hpp>
#include <voltage.hpp>

class Controller_ : Node
{
public:

Controller_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value):
Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value)
, position(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value)
, velocity(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value)
, current(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value)
, voltage(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {};
uint8_t get_state(void);
void set_state(uint8_t value);
uint8_t get_mode(void);
void set_mode(uint8_t value);
uint8_t get_warnings(void);
uint8_t get_errors(void);
Position_ position;
Velocity_ velocity;
Current_ current;
Voltage_ voltage;
void calibrate();
void idle();
void position_mode();
void velocity_mode();
void current_mode();
float set_pos_vel_setpoints(float pos_setpoint, float vel_setpoint);

};
33 changes: 33 additions & 0 deletions include/tinymovr/current.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
/*
* This file was automatically generated using Avlos.
* https://github.com/tinymovr/avlos
*
* Any changes to this file will be overwritten when
* content is regenerated.
*/

#pragma once

#include <helpers.hpp>

class Current_ : Node
{
public:

Current_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value):
Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {};
float get_Iq_setpoint(void);
void set_Iq_setpoint(float value);
float get_Id_setpoint(void);
float get_Iq_limit(void);
void set_Iq_limit(float value);
float get_Iq_estimate(void);
float get_bandwidth(void);
void set_bandwidth(float value);
float get_Iq_p_gain(void);
float get_max_Ibus_regen(void);
void set_max_Ibus_regen(float value);
float get_max_Ibrake(void);
void set_max_Ibrake(float value);

};
28 changes: 28 additions & 0 deletions include/tinymovr/encoder.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,28 @@
/*
* This file was automatically generated using Avlos.
* https://github.com/tinymovr/avlos
*
* Any changes to this file will be overwritten when
* content is regenerated.
*/

#pragma once

#include <helpers.hpp>

class Encoder_ : Node
{
public:

Encoder_(uint8_t _can_node_id, send_callback _send_cb, recv_callback _recv_cb, delay_us_callback _delay_us_cb, uint32_t _delay_us_value):
Node(_can_node_id, _send_cb, _recv_cb, _delay_us_cb, _delay_us_value) {};
float get_position_estimate(void);
float get_velocity_estimate(void);
uint8_t get_type(void);
void set_type(uint8_t value);
float get_bandwidth(void);
void set_bandwidth(float value);
bool get_calibrated(void);
uint8_t get_errors(void);

};
Loading

0 comments on commit 9425279

Please sign in to comment.