7 Commits

35 changed files with 893 additions and 23 deletions

View File

@@ -1,4 +1,4 @@
FROM arm64v8/ros:jazzy as magrob.env
FROM arm64v8/ros:jazzy-ros-base AS magrob.base.env
RUN mkdir -p /ros_ws/src
WORKDIR /ros_ws/src
@@ -7,9 +7,7 @@ RUN --mount=type=bind,source=./,target=/ros_ws/src/ \
--mount=type=cache,target=/var/cache/apt,sharing=locked \
--mount=type=cache,target=/var/lib/apt,sharing=locked \
. /opt/ros/jazzy/setup.sh && \
apt update && \
apt-get install -y ros-jazzy-hardware-interface && \
rosdep install -i --from-paths . -y
scripts/install_base_deps.sh
RUN cat <<EOF >> /root/.bashrc
source /opt/ros/jazzy/setup.bash

View File

@@ -1,9 +1,9 @@
services:
magrob_base:
network_mode: host
image: localhost/magrob.env
image: localhost/magrob.base.env
build:
dockerfile: Dockerfile.env
dockerfile: Dockerfile.base.env
entrypoint: ["sleep","infinity"]
volumes:

5
firmware/base/.vscode/settings.json vendored Normal file
View File

@@ -0,0 +1,5 @@
{
"clangd.arguments": [
"--query-driver=/usr/bin/arm-none-eabi-g*"
]
}

View File

@@ -10,6 +10,7 @@
#define SM_B 1
#define PULSE_PER_REV (1 / 3200.0)
#define SPEED_SET_TIMEOUT 1000
//###############################################
//================ CONFIG ENCODERS =====================

View File

@@ -32,6 +32,7 @@ static double wheel_ratio_r = 1;
static uint prev_time;
static int prev_position_l = 0;
static int prev_position_r = 0;
static uint last_speed_change = 100;
static unsigned char stepper_instr[2+sizeof(double)*2] = {};
@@ -212,6 +213,7 @@ void stepper_fifo(char c, uint8_t itf) {
double vr = btod(stepper_instr + 10);
set_speeds(vl, vr);
last_speed_change = SPEED_SET_TIMEOUT;
// tud_cdc_n_write(itf, (uint8_t const *) stepper_instr, 18);
// tud_cdc_n_write_flush(itf);
@@ -263,6 +265,10 @@ int main()
while (true) {
if(last_speed_change--) {
set_speeds(0, 0);
last_speed_change = SPEED_SET_TIMEOUT;
}
tud_task();
sleep_ms(1);
}

View File

@@ -0,0 +1,63 @@
################################################################################
# #
# Launch file meant to be used on the robot itself #
# uses: #
# * mg_control - for sending commands to the stepper drivers #
# * mg_odometry - for reading and controlling the MCU encoders #
# * mg_navigation - runs the local planner and handles move behaviors #
# * mg_navigation - runs the local planner and handles move behaviors #
# * mg_lidar - optionally runs the lidar node to read opponents #
# positions #
# #
################################################################################
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, GroupAction
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, PythonExpression
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
is_local_test = DeclareLaunchArgument(
'local_test',
default_value="False",
description='Launch with simulated components'
)
return LaunchDescription([
is_local_test,
IncludeLaunchDescription(
PathJoinSubstitution([
FindPackageShare("mg_control"),
'launch',
'toid.launch.py'
]),
launch_arguments={
'use_mock': LaunchConfiguration('local_test')
}.items()
),
Node(
package="mg_odometry",
executable="mg_odom_publisher",
name="mg_odom_publisher",
condition=UnlessCondition(LaunchConfiguration('local_test')),
parameters=[{
'odom': "odom",
'serial_path': "/dev/ttyACM0",
}],
emulate_tty=True,
output='screen'
),
Node(
package="mg_navigation",
executable="mg_nav_server",
name="mg_nav_server",
emulate_tty=True,
output='screen',
)
])

View File

@@ -0,0 +1,29 @@
################################################################################
# #
# Launch file meant to be used on the robot itself #
# uses: #
# * mg_bt - runs the robot's behavior tree server #
# #
################################################################################
from launch import LaunchDescription
from launch.substitutions import PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
def generate_launch_description():
basedir = FindPackageShare("mg_bt")
bt_exec_config = PathJoinSubstitution([basedir, "config/mg_bt_executor.yaml"])
return LaunchDescription([
Node(
package='mg_bt',
executable='mg_bt_executor',
output="screen",
parameters=[bt_exec_config]
),
])

View File

@@ -10,6 +10,7 @@
<buildtool_depend>ament_cmake</buildtool_depend>
<depend>launch</depend>
<depend>launch_ros</depend>
<depend>xacro</depend>
<depend>mg_control</depend>
<depend>mg_odometry</depend>
<depend>mg_navigation</depend>

View File

@@ -37,7 +37,7 @@ set(SOURCES
add_executable(mg_bt_executor ${SOURCES})
add_executable(mg_i2cnode i2cmodule/i2cnode.cpp)
# add_executable(mg_i2cnode i2cmodule/i2cnode.cpp)
target_include_directories(
mg_bt_executor
@@ -46,14 +46,14 @@ target_include_directories(
include
)
target_link_libraries(mg_i2cnode i2c)
# target_link_libraries(mg_i2cnode i2c)
ament_target_dependencies(mg_bt_executor ${PACKAGE_DEPS})
ament_target_dependencies(mg_i2cnode rclcpp mg_msgs)
# ament_target_dependencies(mg_i2cnode rclcpp mg_msgs)
install( TARGETS
mg_bt_executor
mg_i2cnode
# mg_i2cnode
DESTINATION lib/${PROJECT_NAME}
)

View File

@@ -37,7 +37,7 @@ namespace mg {
double theta;
glm::vec2 pos;
auto tmsg = tf_buffer_->lookupTransform("odom", "base-link", tf2::TimePointZero);
auto tmsg = tf_buffer_->lookupTransform("odom", "base_footprint", tf2::TimePointZero);
tf2::Transform t;
tf2::convert(tmsg.transform, t);

View File

@@ -55,7 +55,7 @@
</joint>
<ros2_control name="mg-base" type="system">
<ros2_control name="mg_base" type="system">
<hardware>
<plugin>mg_control/MgStepperInterface</plugin>
</hardware>

View File

@@ -1,6 +1,6 @@
controller_manager:
ros__parameters:
update_rate: 100
update_rate: 50
diffdrive_controller:
type: diff_drive_controller/DiffDriveController
@@ -14,7 +14,7 @@ diffdrive_controller:
enable_odom_tf: false
odom_frame_id: odom_excpected
base_frame_id: base-link
base_frame_id: base_footprint
open_loop: true

View File

@@ -14,7 +14,7 @@ diffdrive_controller:
enable_odom_tf: true
odom_frame_id: odom
base_frame_id: base-link
base_frame_id: base_footprint
open_loop: true

View File

@@ -55,7 +55,7 @@
</joint>
<ros2_control name="mg-base" type="system">
<ros2_control name="mg_base" type="system">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
<param name="calculate_dynamics">true</param>

View File

@@ -0,0 +1,22 @@
controller_manager:
ros__parameters:
update_rate: 50
diffdrive_controller:
type: diff_drive_controller/DiffDriveController
joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster
diffdrive_controller:
ros__parameters:
left_wheel_names: ["drivewhl_l_joint"]
right_wheel_names: ["drivewhl_r_joint"]
enable_odom_tf: true
odom_frame_id: odom
base_frame_id: base_footprint
open_loop: true
wheel_separation: 0.258
wheel_radius: 0.0375

View File

@@ -0,0 +1,111 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import Command, LaunchConfiguration, IfElseSubstitution
from launch_ros.actions import Node, LifecycleNode
from launch_ros.substitutions import FindPackageShare
import os
def generate_launch_description():
pkg_share = FindPackageShare("").find('mg_control')
params = os.path.join(pkg_share, 'assets', 'toid_general_params.yaml')
default_rviz_config_path = os.path.join(pkg_share, 'rviz', 'ros_control.rviz')
description_pkg_share = FindPackageShare("").find('toid_bot_description')
default_model_path = os.path.join(
description_pkg_share,
'src',
'toid_bot_description.urdf'
)
visualize = LaunchConfiguration("visualize")
visualize_arg = DeclareLaunchArgument(
'visualize',
default_value='False',
description="Whether to launch rviz2"
)
use_mock = LaunchConfiguration("use_mock")
use_mock_arg = DeclareLaunchArgument(
'use_mock',
default_value='True',
description="Whether to use mock controller"
)
odom_broadcast = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='map_to_odom_broadcaster',
arguments=['0', '0', '0', '0', '0', '0', 'map', 'odom'],
condition=IfCondition(LaunchConfiguration('visualize'))
)
robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='screen',
parameters=[{'robot_description': Command(['xacro ', default_model_path, ' use_sim:=', use_mock])}]
)
controller_manager = Node(
package='controller_manager',
executable='ros2_control_node',
output='screen',
parameters=[params]
)
joint_state_broadcaster = Node(
package='controller_manager',
executable='spawner',
output='screen',
arguments=["joint_state_broadcaster"]
)
diffbot_base_controller = Node(
package='controller_manager',
executable='spawner',
output='both',
arguments=[
"diffdrive_controller",
"-p",
params,
"--controller-ros-args",
"-r diffdrive_controller/cmd_vel:=/cmd_vel",
"--controller-ros-args",
"-r diffdrive_controller/odom:=/odom",
"--controller-ros-args",
IfElseSubstitution(use_mock,
"--param odom_frame_id:=odom",
"--param odom_frame_id:=odom_expected"
),
"--controller-ros-args",
IfElseSubstitution(use_mock,
"--param enable_odom_tf:=true",
"--param enable_odom_tf:=false"
),
]
)
rviz_node = Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', default_rviz_config_path],
condition=IfCondition(visualize)
)
return LaunchDescription([
visualize_arg,
use_mock_arg,
odom_broadcast,
robot_state_publisher,
controller_manager,
joint_state_broadcaster,
diffbot_base_controller,
rviz_node
])

View File

@@ -1,4 +1,4 @@
rplidar_node:
ros__parameters:
scan_mode: "ppbig"
topic_name: "base-link"
topic_name: "base_link"

View File

@@ -54,7 +54,7 @@ class MgScanner : public rclcpp::Node {
double y = NAN;
double rot = NAN;
auto tmsg = tf_buf_->lookupTransform("odom", "base-link", tf2::TimePointZero);
auto tmsg = tf_buf_->lookupTransform("odom", "base_footprint", tf2::TimePointZero);
tf2::Transform t;
tf2::convert(tmsg.transform, t);

View File

@@ -152,7 +152,7 @@ namespace mg {
double x = NAN;
double y = NAN;
auto tmsg = tfbuf->lookupTransform("odom", "base-link", tf2::TimePointZero);
auto tmsg = tfbuf->lookupTransform("odom", "base_footprint", tf2::TimePointZero);
tf2::Transform t;
tf2::convert(tmsg.transform, t);

View File

@@ -51,7 +51,7 @@ namespace mg {
path_buffer_ = std::make_shared<PathBuffer>(this);
pub_twist = create_publisher<Geometry::TwistStamped>("diffdrive_controller/cmd_vel", 2);
pub_twist = create_publisher<Geometry::TwistStamped>("/cmd_vel", 2);
obstacle_manager_ = std::make_shared<ObstacleManager>(this, tf2_buffer);

View File

@@ -23,7 +23,7 @@
#define TIMEOUT 10u
constexpr const char* ENCODER_SERIAL_PATH_DEFAULT = "/dev/ttyACM1";
constexpr const char* ENCODER_SERIAL_PATH_DEFAULT = "/dev/ttyACM0";
using SendDoubleSrv = mg_msgs::srv::SendDouble;
using ZeroSrv = std_srvs::srv::Empty;
@@ -32,7 +32,7 @@ class MgOdomPublisher : public rclcpp::Node {
public:
MgOdomPublisher() : Node("mg_odom_publisher") {
this->declare_parameter("odom", "odom");
this->declare_parameter("target", "base-link");
this->declare_parameter("target", "base_footprint");
this->declare_parameter("serial_path", ENCODER_SERIAL_PATH_DEFAULT);
tf_broadcaster_ = std::make_shared<tf2_ros::TransformBroadcaster>(this);

View File

@@ -51,7 +51,7 @@ mg::PlannerNode::PlannerNode() : Node("planner"), astar_(this) {
glm::ivec2 mg::PlannerNode::get_pos() {
try {
auto tmsg = tf_buf_->lookupTransform("odom", "base-link", tf2::TimePointZero);
auto tmsg = tf_buf_->lookupTransform("odom", "base_footprint", tf2::TimePointZero);
tf2::Transform t;
tf2::convert(tmsg.transform, t);

55
scripts/docker_build.sh Executable file
View File

@@ -0,0 +1,55 @@
usage() {
cat <<EOF
Usage:
docker_build.sh <target> <registry> [<args>]
docker_build.sh -h
Build and push a docker image to a arm64v8 registry
Targets:
base The pacakges aimed at running on the raspberry pi
EOF
}
TARGET="$1"
REGISTRY="$2"
ARGS="$2"
if [[ $TARGET == "-h" || $TARGET == "--help" ]]; then
usage
exit 0
fi
if [[ $# -lt 2 ]]; then
echo "Error: Expected at least 2 arguments."
usage
exit 1
fi
trap "trap - SIGTERM && kill -- -$$" SIGINT SIGTERM EXIT
case $TARGET in
"base_env")
ssh -N \
-o StrictHostKeyChecking=no \
-o UserKnownHostsFile=/dev/null \
-L 0.0.0.0:5000:localhost:5000 \
$REGISTRY &
echo "Building target: base"
sudo docker buildx build \
--platform linux/arm64 \
-t localhost:5000/magrob.base.env:latest \
-f Dockerfile.base.env \
--output type=registry \
.
;;
*)
echo "Target not defined"
exit 1
;;
esac

17
scripts/install_base_deps.sh Executable file
View File

@@ -0,0 +1,17 @@
#!/bin/bash
ros_distro="jazzy"
script_dir=$(dirname "$(readlink -f "${bash_source[0]}")")
source "/opt/ros/${ROS_DISTRO}/setup.bash"
apt update
apt-get install -y ros-jazzy-hardware-interface # For some reason this package is problamatic
rosdep install -i -y \
--from-paths ./mg_bringup \
--from-paths ./mg_msgs \
--from-paths ./mg_navigation \
--from-paths ./mg_control \
--from-paths ./mg_odometry \
--from-paths ./mg_obstacles \
--from-paths ./mg_lidar

9
scripts/run_base.sh Executable file
View File

@@ -0,0 +1,9 @@
#!/bin/bash
ros_distro="jazzy"
script_dir=$(dirname "$(readlink -f "${bash_source[0]}")")
source "/opt/ros/${ROS_DISTRO}/setup.bash"
source ./install/setup.bash
ros2 launch mg_bringup base.launch.py $@

19
scripts/run_bt.sh Executable file
View File

@@ -0,0 +1,19 @@
#!/bin/bash
ros_distro="jazzy"
script_dir=$(dirname "$(readlink -f "${bash_source[0]}")")
pids=()
source "/opt/ros/${ROS_DISTRO}/setup.bash"
source "./install/setup.bash"
trap "trap - SIGTERM && kill -- -$$" SIGINT SIGTERM EXIT
ros2 launch mg_bringup bt.launch.py & pids+=($!)
sleep 1
ros2 action send_goal /mg_bt_action_server btcpp_ros2_interfaces/action/ExecuteTree "target_tree: $1" & pids+=($!)
wait

View File

@@ -0,0 +1,34 @@
cmake_minimum_required(VERSION 3.8)
project(toid_bot_description)
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)
install(
DIRECTORY
src
launch
rviz
DESTINATION share/${PROJECT_NAME}
)
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()
ament_package()

View File

@@ -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.

View File

@@ -0,0 +1,50 @@
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.conditions import IfCondition, UnlessCondition
from launch.substitutions import Command, LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
import os
def generate_launch_description():
pkg_share = FindPackageShare("").find('toid_bot_description')
default_model_path = os.path.join(pkg_share, 'src', 'toid_bot_description.urdf')
default_rviz_config_path = os.path.join(pkg_share, 'rviz', 'default.rviz')
robot_state_publisher_node = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{'robot_description': Command(['xacro ', LaunchConfiguration('model')])}]
)
joint_state_publisher_node = Node(
package='joint_state_publisher',
executable='joint_state_publisher',
name='joint_state_publisher',
parameters=[{'robot_description': Command(['xacro ', default_model_path])}],
condition=UnlessCondition(LaunchConfiguration('gui'))
)
joint_state_publisher_gui_node = Node(
package='joint_state_publisher_gui',
executable='joint_state_publisher_gui',
name='joint_state_publisher_gui',
condition=IfCondition(LaunchConfiguration('gui'))
)
rviz_node = Node(
package='rviz2',
executable='rviz2',
name='rviz2',
output='screen',
arguments=['-d', default_rviz_config_path]
)
return LaunchDescription([
DeclareLaunchArgument(name='gui', default_value='True', description='Flag to enable joint_state_publisher'),
DeclareLaunchArgument(name='model', default_value=default_model_path, description='Path to model'),
robot_state_publisher_node,
joint_state_publisher_node,
joint_state_publisher_gui_node,
rviz_node
])

View File

@@ -0,0 +1,24 @@
<?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>toid_bot_description</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="example@example.com">pimpest</maintainer>
<license>MIT</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>joint_state_publisher_gui</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>xacro</exec_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>

View File

@@ -0,0 +1,235 @@
Panels:
- Class: rviz_common/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
Splitter Ratio: 0.5
Tree Height: 542
- Class: rviz_common/Selection
Name: Selection
- Class: rviz_common/Tool Properties
Expanded:
- /2D Goal Pose1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz_common/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz_common/Time
Experimental: false
Name: Time
SyncMode: 0
SyncSource: ""
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz_default_plugins/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 0.30000001192092896
Class: rviz_default_plugins/RobotModel
Collision Enabled: false
Description File: ""
Description Source: Topic
Description Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /robot_description
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_footprint:
Alpha: 1
Show Axes: false
Show Trail: false
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
drivewhl_l_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
drivewhl_r_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
left_caster:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
lidar:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
right_caster:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
Mass Properties:
Inertia: false
Mass: false
Name: RobotModel
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz_default_plugins/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: true
base_footprint:
Value: true
base_link:
Value: true
drivewhl_l_link:
Value: true
drivewhl_r_link:
Value: true
left_caster:
Value: true
lidar:
Value: true
right_caster:
Value: true
Marker Scale: 0.30000001192092896
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
base_link:
base_footprint:
{}
drivewhl_l_link:
{}
drivewhl_r_link:
{}
left_caster:
{}
lidar:
{}
right_caster:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Fixed Frame: base_footprint
Frame Rate: 30
Name: root
Tools:
- Class: rviz_default_plugins/Interact
Hide Inactive Objects: true
- Class: rviz_default_plugins/MoveCamera
- Class: rviz_default_plugins/Select
- Class: rviz_default_plugins/FocusCamera
- Class: rviz_default_plugins/Measure
Line color: 128; 128; 0
- Class: rviz_default_plugins/SetInitialPose
Covariance x: 0.25
Covariance y: 0.25
Covariance yaw: 0.06853891909122467
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /initialpose
- Class: rviz_default_plugins/SetGoal
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /goal_pose
- Class: rviz_default_plugins/PublishPoint
Single click: true
Topic:
Depth: 5
Durability Policy: Volatile
History Policy: Keep Last
Reliability Policy: Reliable
Value: /clicked_point
Transformation:
Current:
Class: rviz_default_plugins/TF
Value: true
Views:
Current:
Class: rviz_default_plugins/XYOrbit
Distance: 1.59040105342865
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Focal Point:
X: 0
Y: 0
Z: 0
Focal Shape Fixed Size: false
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.6053992509841919
Target Frame: <Fixed Frame>
Value: XYOrbit (rviz_default_plugins)
Yaw: 1.088563323020935
Saved: ~
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd00000004000000000000016c000002acfc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005d00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003f000002ac000000cc00fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002acfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003f000002ac000000a900fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002de00fffffffb0000000800540069006d0065010000000000000450000000000000000000000229000002ac00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 60
Y: 60

View File

@@ -0,0 +1,35 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="toid_control" params="name:=toid_control use_mock_hardware:=^|true">
<ros2_control name="${name}" type="system">
<xacro:unless value="${use_mock_hardware}">
<hardware>
<plugin>mg_control/MgStepperInterface</plugin>
</hardware>
</xacro:unless>
<xacro:if value="${use_mock_hardware}">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
<param name="calculate_dynamics">true</param>
</hardware>
</xacro:if>
<joint name="drivewhl_l_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="drivewhl_r_joint">
<command_interface name="velocity"/>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>

View File

@@ -0,0 +1,117 @@
<?xml version="1.0"?>
<robot name="toid_bot" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="use_mock" default="true" />
<xacro:property name="base_width" value="0.30"/>
<xacro:property name="base_length" value="0.30"/>
<xacro:property name="base_height" value="0.34"/>
<xacro:property name="wheel_radius" value="0.04"/>
<xacro:property name="wheel_width" value="0.03"/>
<xacro:property name="wheel_zoff" value="0.03"/>
<xacro:property name="wheel_xoff" value="-0.07"/>
<xacro:property name="wheel_inset" value="0.01"/>
<xacro:property name="caster_radius" value="0.02"/>
<xacro:property name="caster_inset" value="0.04"/>
<xacro:property name="caster_xoff" value="0.10"/>
<xacro:property name="lidar_radius" value="0.03"/>
<xacro:property name="lidar_height" value="0.02"/>
<xacro:property name="lidar_xoff" value="0.09"/>
<xacro:property name="base_zoff" value="${-wheel_zoff + wheel_radius + base_height/2}"/>
<link name="base_link">
<visual>
<geometry>
<box size="${base_length} ${base_width} ${base_height}"/>
</geometry>
<material name="Cyan">
<color rgba="0 1.0 1.0 1.0"/>
</material>
</visual>
</link>
<link name="base_footprint"/>
<link name="lidar">
<visual>
<geometry>
<cylinder radius="${lidar_radius}" length="${lidar_height}"/>
</geometry>
<material name="White">
<color rgba="0.9 0.9 0.9 1.0"/>
</material>
</visual>
</link>
<joint name="base_joint" type="fixed">
<child link="base_link"/>
<parent link="base_footprint"/>
<origin xyz="${-wheel_xoff} 0.0 ${base_zoff}" rpy="0 0 0"/>
</joint>
<joint name="lidar_joint" type="fixed">
<parent link="base_link"/>
<child link="lidar"/>
<origin xyz="${lidar_xoff} 0 ${(base_height + lidar_height)/2}" rpy="0 0 0"/>
</joint>
<xacro:macro name="wheel" params="prefix y_reflect">
<link name="${prefix}_link">
<visual>
<origin xyz="0 0 0" rpy="${pi/2} 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
</geometry>
<material name="Yellow">
<color rgba="0.8 0.8 0.3 1.0"/>
</material>
</visual>
</link>
<joint name="${prefix}_joint" type="continuous">
<parent link="base_link"/>
<child link="${prefix}_link"/>
<origin xyz="${wheel_xoff} ${y_reflect*(base_width/2 - wheel_inset)} ${wheel_zoff-base_height/2}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>
</xacro:macro>
<xacro:macro name="cstr" params="prefix y_reflect">
<link name="${prefix}_caster">
<visual>
<geometry>
<sphere radius="${caster_radius}"/>
</geometry>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
</visual>
</link>
<joint name="${prefix}_caster_joint" type="fixed">
<parent link="base_link"/>
<child link="${prefix}_caster"/>
<origin xyz="${caster_xoff} ${y_reflect*(base_width/2 - caster_inset)} ${caster_radius-base_zoff}" rpy="0 0 0"/>
</joint>
</xacro:macro>
<xacro:wheel prefix="drivewhl_l" y_reflect="1" />
<xacro:wheel prefix="drivewhl_r" y_reflect="-1" />
<xacro:cstr prefix="left" y_reflect="1" />
<xacro:cstr prefix="right" y_reflect="-1" />
<xacro:include filename="$(find toid_bot_description)/src/toid_bot_control.xacro"/>
<xacro:toid_control name="toid_bot_control" use_mock_hardware="$(arg use_mock)"/>
</robot>

View File

@@ -0,0 +1,9 @@
version: 0.1
storage:
filesystem:
rootdirectory: /var/lib/registry
http:
addr: :5000
headers:
X-Content-Type-Options: [nosniff]

View File

@@ -0,0 +1,13 @@
services:
registry:
restart: always
image: registry:2
ports:
- 5000:5000
environment:
REGISTRY_HTTP_TLS_CERTIFICATE: /certs/domain.crt
REGISTRY_HTTP_TLS_KEY: /certs/domain.key
REGISTRY_STORAGE_FILESYSTEM_ROOTDIRECTORY: /var/lib/registry
volumes:
- ./config/config.yml:/etc/docker/registry/config.yml:ro
- ./data:/var/lib/registry:rw