Skip to content

Commit

Permalink
Merge pull request #13 from WHILL/melodic-generation-2
Browse files Browse the repository at this point in the history
ros_whill 2.0.
ros-melodic is only supported as of June 11.
ros-kinetic support will be followed upon request.
  • Loading branch information
Seiya Shimizu authored Jun 11, 2019
2 parents 6b9491d + ea5f879 commit aac3736
Show file tree
Hide file tree
Showing 34 changed files with 1,713 additions and 1,328 deletions.
33 changes: 18 additions & 15 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,12 +13,15 @@ find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
tf
serial
)

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)


add_subdirectory(./src/whill)

## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
Expand Down Expand Up @@ -51,16 +54,13 @@ find_package(catkin REQUIRED COMPONENTS
## Generate messages in the 'msg' folder
add_message_files(
FILES
msgWhillModelC.msg
msgWhillSpeedProfile.msg
)
SpeedPack.msg
)

## Generate services in the 'srv' folder
add_service_files(
FILES
srvSetSpeedProfile.srv
srvSetPower.srv
srvSetBatteryVoltageOut.srv
SetSpeedProfile.srv
)

## Generate actions in the 'action' folder
Expand All @@ -74,6 +74,7 @@ find_package(catkin REQUIRED COMPONENTS
generate_messages(
DEPENDENCIES
std_msgs
ros_whill
)

################################################
Expand Down Expand Up @@ -137,8 +138,8 @@ include_directories(
## 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/ros_whill_node.cpp)
add_executable(whill_modelc_publisher src/whill_modelc_publisher.cpp src/whill_modelc/uart.cpp src/whill_modelc/com_whill.cpp src/odom.cpp)
add_executable(whill_modelc_controller src/whill_modelc_controller.cpp src/whill_modelc/uart.cpp src/whill_modelc/com_whill.cpp)
add_executable(ros_whill src/ros_whill.cpp src/odom.cpp src/utils/rotation_tools.cpp src/utils/unit_convert.cpp)


## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
Expand All @@ -149,15 +150,17 @@ add_executable(whill_modelc_controller src/whill_modelc_controller.cpp src/whill
## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(whill_modelc_publisher ${PROJECT_NAME}_generate_messages_cpp ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(whill_modelc_controller ${PROJECT_NAME}_generate_messages_cpp ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
# add_dependencies(whill_modelc_publisher ${PROJECT_NAME}_generate_messages_cpp ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
# add_dependencies(whill_modelc_controller ${PROJECT_NAME}_generate_messages_cpp ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(ros_whill ${PROJECT_NAME}_generate_messages_cpp ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

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

#target_link_libraries(ros_whill ${catkin_LIBRARIES})

#############
## Install ##
Expand Down
88 changes: 56 additions & 32 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,48 +5,77 @@ For general questions and requests, please visit https://whill.zendesk.com/hc/ja

<img src="https://user-images.githubusercontent.com/2618822/45492944-89421c00-b7a8-11e8-9c92-22aa3f28f6e4.png" width=30%>

## Requirements
- ROS Melodic

## ROS API

### Subscribed Topics

#### /whill/controller/joy [(sensor_msgs/Joy)](http://docs.ros.org/api/sensor_msgs/html/msg/Joy.html)
#### ~controller/joy [(sensor_msgs/Joy)](http://docs.ros.org/api/sensor_msgs/html/msg/Joy.html)
- Virtual WHILL joystick input. You can controll WHILL via this topic.


### Published Topics

#### /whill/states/joy [(sensor_msgs/Joy)](http://docs.ros.org/api/sensor_msgs/html/msg/Joy.html)
#### ~states/joy [(sensor_msgs/Joy)](http://docs.ros.org/api/sensor_msgs/html/msg/Joy.html)
- Joystick status

#### /whill/states/jointState [(sensor_msgs/JointState)](http://docs.ros.org/api/sensor_msgs/html/msg/JointState.html)
#### ~states/jointState [(sensor_msgs/JointState)](http://docs.ros.org/api/sensor_msgs/html/msg/JointState.html)
- Wheel rotate position(rad) and rotation velocity(rad/s)

#### /whill/states/imu [(sensor_msgs/Imu)](http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html)
#### ~states/imu [(sensor_msgs/Imu)](http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html)
- IMU measured data.

#### /whill/states/batteryState [(sensor_msgs/BatteryState)](http://docs.ros.org/api/sensor_msgs/html/msg/BatteryState.html)
#### ~states/batteryState [(sensor_msgs/BatteryState)](http://docs.ros.org/api/sensor_msgs/html/msg/BatteryState.html)
- Battery information


## Requirements
- Ubuntu 16.04
- ROS kinetic
### Services

## Build
In your shell:
```sh
cd ~/catkin_ws
catkin_make
rospack profile
#### ~odom/clear [std_srvs/Empty]
Clear Odometry

#### ~power [std_srvs/SetBool]
True to send power on command, false to power off.

#### ~speedProfile/set [ros_whill/SetSpeedProfile]
You can set WHILL speed profile for `~controller/joy` topic.
```
ros_whill package is sometimes not recognized if you not set "rospack profile". (After executed "rosrun ros_whill", you might see the error message "not found package".)
ros_whill/SpeedPack forward
float32 speed # m/s
float32 acc # m/ss
float32 dec # m/ss
ros_whill/SpeedPack backward
float32 speed # m/s
float32 acc # m/ss
float32 dec # m/ss
ros_whill/SpeedPack turn
float32 speed # rad/s
float32 acc # rad/ss
float32 dec # rad/ss
---
bool success
string status_message
### Build only ros_whill package
```sh
catkin_make -DCATKIN_WHITELIST_PACKAGES="ros_whill"
```

## SerialPort Settings
### Parameters

### ~init_speed/*
See:

### ~keep_connected (Bool, default:false)
Set true to try to keep connected by re-opening port and sending power-on command. Though the WHILL automticarry wakes up even you turn off manualy or by power-off command.

### ~publish_tf (Bool, defualt: true)
False to stop publishing `odom` to `base_link` tf. If other node publishs, set value to false.

### ~serialport (String, default:/dev/ttyUSB0)


## SerialPort Setting for ros_whill.launch
The `ros_whill.launch` is using environmental variable `TTY_WHILL` for specify which serial port to be used.

### Set

Expand Down Expand Up @@ -76,17 +105,6 @@ source ~/.zshrc
echo $TTY_WHILL # -> Should be /dev/[YOUR SERIAL PORT DEVICE]
```

## Launch
```sh
roslaunch ros_whill modelc.launch
```

### Set serial port as an argument of the launch file
```sh
roslaunch ros_whill modelc.launch serialport:=/dev/[YOUR SERIAL PORT DEVICE]
```


### In the case of opening serial port failed

Edit
Expand All @@ -99,7 +117,13 @@ And add:
KERNEL=="ttyUSB[0-9]*", MODE="0666"
```

## Change Speed Profile

## Launch with Model
```sh
$ roslaunch ros_whill ros_whill.launch
```

### Set serial port as an argument of the launch file
```sh
rosservice call /set_speed_profile {4, 15, 16, 64, 10, 16, 56, 10, 56, 72}
roslaunch ros_whill ros_whill.launch serialport:=/dev/[YOUR SERIAL PORT DEVICE]
```
21 changes: 0 additions & 21 deletions launch/modelc.launch

This file was deleted.

32 changes: 32 additions & 0 deletions launch/ros_whill.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
<launch>
<arg name="model" default="$(find ros_whill)/xacro/modelc.xacro" />
<arg name="gui" default="true" />

<param name="robot_description" command="$(find xacro)/xacro $(arg model)"/>

<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher">
<remap from="/joint_states" to="/whill/states/jointState" />
</node>

<arg name="serialport" default="$(env TTY_WHILL)"/>

<node pkg="ros_whill" type="ros_whill" name="whill" output="screen" >

<!-- Initial Speed Profile -->
<rosparam file="$(find ros_whill)/params/initial_speedprofile.yaml" command="load" />

<!-- Keep Connected: If you specify true,ros_whill try to keep connection by re-opening port and sending power on command.
If you'd like to turn WHILL off by command or manually while using ros_whill, set value to false.
Otherwise WHILL automatically turns on.
-->
<param name="keep_connected" value="true" />

<!-- Serial Device name -->
<param name="serialport" value="$(arg serialport)"/>

<!-- Output Odometry tf or not. If other node publishes odom->base_link tf, Change value to "false" -->
<param name="publish_tf" value="true"/>

</node>
</launch>

8 changes: 0 additions & 8 deletions launch/teleop_joy.launch

This file was deleted.

3 changes: 3 additions & 0 deletions msg/SpeedPack.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
float32 speed # m/s or rad/s
float32 acc # m/ss or rad/ss
float32 dec # m/ss or rad/ss
17 changes: 0 additions & 17 deletions msg/msgWhillModelC.msg

This file was deleted.

11 changes: 0 additions & 11 deletions msg/msgWhillSpeedProfile.msg

This file was deleted.

3 changes: 2 additions & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -53,13 +53,14 @@
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>

<depend>serial</depend>

<!-- The export tag contains other, unspecified, tags -->
<export>
Expand Down
12 changes: 12 additions & 0 deletions params/initial_speedprofile.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
#
# Initial Speed Profile
#
init_speed/forward/speed: 0.567 # [m/s]
init_speed/forward/acc: 0.23 # [m/ss]
init_speed/forward/dec: 1.25 # [m/ss]
init_speed/backward/speed: 0.557 # [m/s]
init_speed/backward/acc: 0.34 # [m/ss]
init_speed/backward/dec: 0.89 # [m/ss]
init_speed/turn/speed: 0.8 # [rad/s]
init_speed/turn/acc: 0.79 # [rad/ss]
init_speed/turn/dec: 1.8 # [rad/ss]
Loading

0 comments on commit aac3736

Please sign in to comment.