Merge remote changes

This commit is contained in:
Minh MENG HOUR 2023-08-30 01:53:43 -07:00
commit cf59b4cd5c
14 changed files with 607 additions and 41 deletions

1
.catkin_workspace Normal file
View File

@ -0,0 +1 @@
# This file currently only serves to mark the location of a catkin workspace for tool integration

21
.vscode/c_cpp_properties.json vendored Normal file
View File

@ -0,0 +1,21 @@
{
"configurations": [
{
"browse": {
"databaseFilename": "${default}",
"limitSymbolsToIncludedHeaders": false
},
"includePath": [
"/opt/ros/noetic/include/**",
"/home/sasu/kubot_ws/src/kubot_description/include/**",
"/usr/include/**"
],
"name": "ROS",
"intelliSenseMode": "gcc-x64",
"compilerPath": "/usr/bin/gcc",
"cStandard": "gnu11",
"cppStandard": "c++14"
}
],
"version": 4
}

8
.vscode/settings.json vendored Normal file
View File

@ -0,0 +1,8 @@
{
"python.autoComplete.extraPaths": [
"/opt/ros/noetic/lib/python3/dist-packages"
],
"python.analysis.extraPaths": [
"/opt/ros/noetic/lib/python3/dist-packages"
]
}

View File

@ -6,6 +6,10 @@ find_package(catkin REQUIRED COMPONENTS
rospy
std_msgs
geometry_msgs
sensor_msgs
nav_msgs
tf2
tf2_ros
)
find_package(Eigen3 REQUIRED)
@ -14,6 +18,10 @@ INCLUDE_DIRS include
CATKIN_DEPENDS
std_msgs
geometry_msgs
sensor_msgs
nav_msgs
tf2
tf2_ros
DEPENDS Eigen3
# DEPENDS system_lib
)

View File

@ -1,18 +1,44 @@
#ifndef SIMPLE_CONTROLLER_H
#define SIMPLE_CONTROLLER_H
#include <ros/ros.h>
#include <geometry_msgs/Twist.h>
#include <Eigen/Core>
#include <sensor_msgs/JointState.h>
#include <nav_msgs/Odometry.h>
#include <geometry_msgs/TransformStamped.h>
class SimpleController
{
public:
SimpleController(const ros::NodeHandle & ,double radius, double seperation);
private:
void velCallBack(const geometry_msgs::Twist &);
public:
SimpleController(const ros::NodeHandle &, double radius, double separation);
private:
void velCallback(const geometry_msgs::Twist &);
void jointCallback(const sensor_msgs::JointState &);
ros::NodeHandle nh_;
ros::Subscriber vel_sub_;
ros::Publisher right_cmd_pub_;
ros::Publisher left_cmd_pub_;
ros::Subscriber joint_sub_;
ros::Publisher odom_pub_;
// Differential Kinematics
Eigen::Matrix2d speed_conversion_;
// Odometry
double wheel_radius_;
double wheel_separation_;
double right_wheel_prev_pos_;
double left_wheel_prev_pos_;
ros::Time prev_time_;
nav_msgs::Odometry odom_msg_;
double x_;
double y_;
double theta_;
geometry_msgs::TransformStamped transform_stamped_;
};
#endif
#endif

View File

@ -1,15 +1,17 @@
#include <ros/ros.h>
#include "turtlebot_controller/simple_controller.h"
int main(int argc, char **argv){
int main(int argc, char **argv)
{
ros::init(argc, argv, "simple_controller");
ros::NodeHandle nh;
ros::NodeHandle pnh("~");
double wheel_radius;
double wheel_radius, wheel_separation;
pnh.getParam("wheel_radius", wheel_radius);
double wheel_seperation;
pnh.getParam("wheel_seperation", wheel_seperation);
SimpleController controller(nh, wheel_radius, wheel_seperation);
pnh.getParam("wheel_separation", wheel_separation);
SimpleController controller(nh, wheel_radius, wheel_separation);
ros::spin();
return 0;
}

View File

@ -54,14 +54,26 @@
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>eigen</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>nav_msgs</build_depend>
<build_depend>tf2</build_depend>
<build_depend>tf2_ros</build_depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>eigen</build_export_depend>
<build_export_depend>sensor_msgs</build_export_depend>
<build_export_depend>nav_msgs</build_export_depend>
<build_export_depend>tf2</build_export_depend>
<build_export_depend>tf2_ros</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>eigen</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>nav_msgs</exec_depend>
<exec_depend>tf2</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>

View File

@ -1,29 +1,116 @@
#include <turtlebot_controller/simple_controller.h>
#include "turtlebot_controller/simple_controller.h"
#include <std_msgs/Float64.h>
#include <Eigen/Geometry>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/transform_broadcaster.h>
SimpleController::SimpleController(const ros::NodeHandle &nh ,double radius, double seperation): nh_(nh)
SimpleController::SimpleController(const ros::NodeHandle &nh,
double radius,
double separation)
: nh_(nh)
, wheel_radius_(radius)
, wheel_separation_(separation)
, left_wheel_prev_pos_(0.0)
, right_wheel_prev_pos_(0.0)
, x_(0.0)
, y_(0.0)
, theta_(0.0)
{
ROS_INFO_STREAM("Using wheel raduis" << radius);
ROS_INFO_STREAM("Using wheel seperation" << seperation);
ROS_INFO_STREAM("Using wheel radius " << radius);
ROS_INFO_STREAM("Using wheel separation " << separation);
right_cmd_pub_ = nh_.advertise<std_msgs::Float64>("wheel_right_controller/command", 10);
left_cmd_pub_ = nh_.advertise<std_msgs::Float64>("wheel_left_controller/command", 10);
vel_sub_ = nh_.subscribe("turtlebot_controller/cmd_vel", 1000, &SimpleController::velCallback, this);
joint_sub_ = nh_.subscribe("joint_states", 1000, &SimpleController::jointCallback, this);
odom_pub_ = nh_.advertise<nav_msgs::Odometry>("turtlebot_controller/odom", 10);
vel_sub_ = nh_.subscribe("turtlebot_controller/cmd.vel", 1000, &SimpleController::velCallBack, this);
speed_conversion_ <<radius/2, radius/2, radius/seperation, -radius/seperation;
speed_conversion_ << radius/2, radius/2, radius/separation, -radius/separation;
ROS_INFO_STREAM("The conversion matrix is \n" << speed_conversion_);
// Fill the Odometry message with invariant parameters
odom_msg_.header.frame_id = "odom";
odom_msg_.child_frame_id = "base_footprint";
odom_msg_.pose.pose.orientation.x = 0.0;
odom_msg_.pose.pose.orientation.y = 0.0;
odom_msg_.pose.pose.orientation.z = 0.0;
odom_msg_.pose.pose.orientation.w = 1.0;
transform_stamped_.header.frame_id = "odom";
transform_stamped_.child_frame_id = "base_footprint";
prev_time_ = ros::Time::now();
}
void SimpleController::velCallBack(const geometry_msgs::Twist &msg)
void SimpleController::velCallback(const geometry_msgs::Twist &msg)
{
// Implements the differential kinematic model
// Given v and w, calculate the velocities of the wheels
Eigen::Vector2d robot_speed(msg.linear.x, msg.angular.z);
Eigen::Vector2d wheel_speed = speed_conversion_.inverse() * robot_speed;
std_msgs::Float64 right_speed;
right_speed.data = wheel_speed.coeff(0);
std_msgs::Float64 left_speed;
right_speed.data =wheel_speed.coeff(0);
left_speed.data = wheel_speed.coeff(1);
right_cmd_pub_.publish(right_speed);
left_cmd_pub_.publish(left_speed);
}
void SimpleController::jointCallback(const sensor_msgs::JointState &state)
{
// Implements the inverse differential kinematic model
// Given the position of the wheels, calculates their velocities
// then calculates the velocity of the robot wrt the robot frame
// and then converts it in the global frame and publishes the TF
double dp_left = state.position.at(0) - left_wheel_prev_pos_;
double dp_right = state.position.at(1) - right_wheel_prev_pos_;
double dt = (state.header.stamp - prev_time_).toSec();
// Actualize the prev pose for the next itheration
left_wheel_prev_pos_ = state.position.at(0);
right_wheel_prev_pos_ = state.position.at(1);
prev_time_ = state.header.stamp;
// Calculate the rotational speed of each wheel
double fi_left = dp_left / dt;
double fi_right = dp_right / dt;
// Calculate the linear and angular velocity
double linear = (wheel_radius_ * fi_right + wheel_radius_ * fi_left) / 2;
double angular = (wheel_radius_ * fi_right - wheel_radius_ * fi_left) / wheel_separation_;
// Calculate the position increment
double d_s = (wheel_radius_ * dp_right + wheel_radius_ * dp_left) / 2;
double d_theta = (wheel_radius_ * dp_right - wheel_radius_ * dp_left) / wheel_separation_;
theta_ += d_theta;
x_ += d_s * cos(theta_);
y_ += d_s * sin(theta_);
// Compose and publish the odom message
tf2::Quaternion q;
q.setRPY(0, 0, theta_);
odom_msg_.header.stamp = ros::Time::now();
odom_msg_.pose.pose.position.x = x_;
odom_msg_.pose.pose.position.y = y_;
odom_msg_.pose.pose.orientation.x = q.getX();
odom_msg_.pose.pose.orientation.y = q.getY();
odom_msg_.pose.pose.orientation.z = q.getZ();
odom_msg_.pose.pose.orientation.w = q.getW();
odom_msg_.twist.twist.linear.x = linear;
odom_msg_.twist.twist.angular.z = angular;
odom_pub_.publish(odom_msg_);
// TF
static tf2_ros::TransformBroadcaster br;
transform_stamped_.transform.translation.x = x_;
transform_stamped_.transform.translation.y = y_;
transform_stamped_.transform.rotation.x = q.getX();
transform_stamped_.transform.rotation.y = q.getY();
transform_stamped_.transform.rotation.z = q.getZ();
transform_stamped_.transform.rotation.w = q.getW();
transform_stamped_.header.stamp = ros::Time::now();
br.sendTransform(transform_stamped_);
}

View File

@ -0,0 +1,21 @@
<launch>
<arg name="model" default="$(find kubot_description)/urdf/kubot.urdf.xacro"/>
<arg name="world" default="$(find kubot_description)/worlds/ku_lab/ku_model.sdf"/>
<!-- <arg name="world" default="empty_world"/> -->
<param name="robot_description" command="$(find xacro)/xacro '$(find turtlebot_description)/urdf/turtlebot.urdf.xacro'" />
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="world_name" value="$(arg world)"/>
<arg name="paused" value="false"/>
<arg name="use_sim_time" value="true"/>
<arg name="gui" value="true"/>
<arg name="recording" value="false"/>
<arg name="debug" value="false"/>
</include>
<node pkg="gazebo_ros" type="spawn_model" name="spawn_model"
args="-unpause -urdf -model robot -param robot_description"
output="screen" respawn="false"/>
</launch>

View File

@ -23,7 +23,7 @@
<collision>
<origin xyz="-0.064 0 0.047" rpy="0 0 0"/>
<geometry>
<box size="0.266 0.266 0.094"/>
<box size="0.266 0.266 0.094"/>
</geometry>
</collision>
@ -48,7 +48,7 @@
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<cylinder length="0.018" radius="0.033"/>
<cylinder length="0.018" radius="0.033"/>
</geometry>
</collision>
@ -93,8 +93,29 @@
</inertial>
</link>
<<<<<<< HEAD
<<<<<<< HEAD
<link name="caster_back_right_link">
=======
<link name="caster_link">
<collision>
<origin xyz="0 0.001 0" rpy="0 0 0"/>
<geometry>
<box size="0.030 0.009 0.020"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" />
<mass value="0.005" />
<inertia ixx="0.001" ixy="0.0" ixz="0.0"
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>
<!-- <link name="caster_back_right_link">
>>>>>>> c06338a682c5cc259374cb313033cea656328708
<collision>
<origin xyz="0 0.001 0" rpy="0 0 0"/>
=======
@ -134,7 +155,7 @@
iyy="0.001" iyz="0.0"
izz="0.001" />
</inertial>
</link>
</link> -->
=======
>>>>>>> devolop
@ -164,8 +185,12 @@
izz="0.001" />
</inertial>
</link>
<<<<<<< HEAD
<<<<<<< HEAD
=======
<!--
>>>>>>> c06338a682c5cc259374cb313033cea656328708
<link name="camera_link">
=======
<!-- <link name="camera_link">
@ -176,15 +201,19 @@
<box size="0.015 0.030 0.027"/>
</geometry>
</collision>
</link>
</link> -->
<link name="camera_rgb_frame"/>
<!-- <link name="camera_rgb_frame"/> -->
<<<<<<< HEAD
<<<<<<< HEAD
<link name="camera_rgb_optical_frame"/>
=======
<link name="camera_rgb_optical_frame"/> -->
>>>>>>> devolop
=======
<!-- <link name="camera_rgb_optical_frame"/> -->
>>>>>>> c06338a682c5cc259374cb313033cea656328708
<joint name="base_joint" type="fixed">
<parent link="base_footprint"/>
@ -205,7 +234,7 @@
<origin xyz="0.0 -0.144 0.023" rpy="-1.57 0 0"/>
<axis xyz="0 0 1"/>
</joint>
<!--
<joint name="caster_back_right_joint" type="fixed">
<parent link="base_link"/>
<<<<<<< HEAD
@ -217,6 +246,12 @@
<parent link="base_link"/>
<child link="caster_back_left_link"/>
<origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/>
</joint> -->
<joint name="caster_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_link"/>
<origin xyz="-0.177 0.064 -0.004" rpy="-1.57 0 0"/>
</joint>
=======
<child link="caster_back"/>
@ -238,30 +273,38 @@
<origin xyz="-0.024 0 0.122" rpy="0 0 0"/>
</joint>
<<<<<<< HEAD
<<<<<<< HEAD
<joint name="camera_joint" type="fixed">
=======
<!-- <joint name="camera_joint" type="fixed">
>>>>>>> devolop
=======
<!-- <joint name="camera_joint" type="fixed">
>>>>>>> c06338a682c5cc259374cb313033cea656328708
<origin xyz="0.073 -0.011 0.084" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="camera_link"/>
</joint>
</joint> -->
<!--
<joint name="camera_rgb_joint" type="fixed">
<origin xyz="0.003 0.011 0.009" rpy="0 0 0"/>
<parent link="camera_link"/>
<child link="camera_rgb_frame"/>
</joint>
</joint> -->
<joint name="camera_rgb_optical_joint" type="fixed">
<!-- <joint name="camera_rgb_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-1.57 0 -1.57"/>
<parent link="camera_rgb_frame"/>
<child link="camera_rgb_optical_frame"/>
<<<<<<< HEAD
<<<<<<< HEAD
</joint>
=======
</joint> -->
>>>>>>> devolop
=======
</joint> -->
>>>>>>> c06338a682c5cc259374cb313033cea656328708
</robot>

View File

@ -32,18 +32,7 @@
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="caster_back_right_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<kp>1000000</kp>
<kd>100</kd>
<minDepth>0.001</minDepth>
<maxVel>1</maxVel>
<fdir1>1 0 0</fdir1>
<material>Gazebo/FlatBlack</material>
</gazebo>
<gazebo reference="caster_back_left_link">
<gazebo reference="caster_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<kp>1000000</kp>
@ -82,4 +71,33 @@
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</actuator>
</transmission>
<gazebo reference="base_scan">
<sensor name="laser" type="ray">
<pose> 0 0 0 0 0 0 </pose>
<visualize>true</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<min_angle>-3.14</min_angle>
<max_angle>3.14</max_angle>
</horizontal>
</scan>
<range>
<min>0.3</min>
<max>12</max>
</range>
</ray>
<plugin name="laser_controller" filename="libgazebo_ros_ray_sensor.so">
<ros>
<argument>~/out:=scan</argument>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>laser_frame</frame_name>
</plugin>
</sensor>
</gazebo>
</robot>

View File

@ -0,0 +1,202 @@
cmake_minimum_required(VERSION 3.0.2)
project(turtlebot_slam)
## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)
## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED)
## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)
## 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
# catkin_python_setup()
################################################
## Declare ROS messages, services and actions ##
################################################
## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a exec_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a exec_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)
## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# std_msgs # Or other packages containing msgs
# )
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a exec_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed
## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )
###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES turtlebot_slam
# CATKIN_DEPENDS other_catkin_pkg
# DEPENDS system_lib
)
###########
## Build ##
###########
## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
# ${catkin_INCLUDE_DIRS}
)
## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/turtlebot_slam.cpp
# )
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## 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/turtlebot_slam_node.cpp)
## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")
## 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})
## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )
#############
## Install ##
#############
# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html
## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# catkin_install_python(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark executables for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_executables.html
# install(TARGETS ${PROJECT_NAME}_node
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
## Mark libraries for installation
## See http://docs.ros.org/melodic/api/catkin/html/howto/format1/building_libraries.html
# install(TARGETS ${PROJECT_NAME}
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION}
# )
## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
## Mark other files for installation (e.g. launch and bag files, etc.)
# install(FILES
# # myfile1
# # myfile2
# DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
# )
#############
## Testing ##
#############
## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_turtlebot_slam.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
## Add folders to be run by python nosetests
# catkin_add_nosetests(test)

View File

@ -0,0 +1,58 @@
-- Copyright 2016 The Cartographer Authors
--
-- 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.
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
-- tracking_frame = "imu_link", -- imu_link, If you are using gazebo, use 'base_footprint' (libgazebo_ros_imu's bug)
tracking_frame = "base_footprint"
published_frame = "odom",
odom_frame = "odom",
provide_odom_frame = false,
publish_frame_projected_to_2d = false,
use_odometry = true,
use_nav_sat = false,
use_landmarks = false,
num_laser_scans = 1,
num_multi_echo_laser_scans = 0,
num_subdivisions_per_laser_scan = 1,
num_point_clouds = 0,
lookup_transform_timeout_sec = 0.2,
submap_publish_period_sec = 0.3,
pose_publish_period_sec = 5e-3,
trajectory_publish_period_sec = 30e-3,
rangefinder_sampling_ratio = 1.,
odometry_sampling_ratio = 0.1,
fixed_frame_pose_sampling_ratio = 1.,
imu_sampling_ratio = 0.1,
landmarks_sampling_ratio = 1.,
}
MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.min_range = 0.1
TRAJECTORY_BUILDER_2D.max_range = 3.5
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 3.
TRAJECTORY_BUILDER_2D.use_imu_data = true
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.1)
POSE_GRAPH.constraint_builder.min_score = 0.65
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7
return options

View File

@ -0,0 +1,59 @@
<?xml version="1.0"?>
<package format="2">
<name>turtlebot_slam</name>
<version>0.0.0</version>
<description>The turtlebot_slam package</description>
<!-- One maintainer tag required, multiple allowed, one person per tag -->
<!-- Example: -->
<!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> -->
<maintainer email="sasu@todo.todo">sasu</maintainer>
<!-- One license tag required, multiple allowed, one license per tag -->
<!-- Commonly used license strings: -->
<!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 -->
<license>TODO</license>
<!-- Url tags are optional, but multiple are allowed, one per tag -->
<!-- Optional attribute type can be: website, bugtracker, or repository -->
<!-- Example: -->
<!-- <url type="website">http://wiki.ros.org/turtlebot_slam</url> -->
<!-- Author tags are optional, multiple are allowed, one per tag -->
<!-- Authors do not have to be maintainers, but could be -->
<!-- Example: -->
<!-- <author email="jane.doe@example.com">Jane Doe</author> -->
<!-- The *depend tags are used to specify dependencies -->
<!-- Dependencies can be catkin packages or system dependencies -->
<!-- Examples: -->
<!-- Use depend as a shortcut for packages that are both build and exec dependencies -->
<!-- <depend>roscpp</depend> -->
<!-- Note that this is equivalent to the following: -->
<!-- <build_depend>roscpp</build_depend> -->
<!-- <exec_depend>roscpp</exec_depend> -->
<!-- Use build_depend for packages you need at compile time: -->
<!-- <build_depend>message_generation</build_depend> -->
<!-- Use build_export_depend for packages you need in order to build against this package: -->
<!-- <build_export_depend>message_generation</build_export_depend> -->
<!-- Use buildtool_depend for build tool packages: -->
<!-- <buildtool_depend>catkin</buildtool_depend> -->
<!-- Use exec_depend for packages you need at runtime: -->
<!-- <exec_depend>message_runtime</exec_depend> -->
<!-- Use test_depend for packages you need only for testing: -->
<!-- <test_depend>gtest</test_depend> -->
<!-- Use doc_depend for packages you need only for building documentation: -->
<!-- <doc_depend>doxygen</doc_depend> -->
<buildtool_depend>catkin</buildtool_depend>
<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->
</export>
</package>