Merge branch 'galactic-adjustments' into nav2_setup

This commit is contained in:
Your Name 2023-07-13 14:56:46 +02:00
commit 8c64697375
10 changed files with 26 additions and 17 deletions

View File

@ -22,6 +22,7 @@ def generate_launch_description():
# Process the URDF file # Process the URDF file
pkg_path = os.path.join(get_package_share_directory('dcaiti_control')) pkg_path = os.path.join(get_package_share_directory('dcaiti_control'))
xacro_file = os.path.join(pkg_path,'description','robot.urdf.xacro') xacro_file = os.path.join(pkg_path,'description','robot.urdf.xacro')
# xacro_file = "/home/nvidia/ros2_humble/src/turtlebot3_simulations/turtlebot3_gazebo/urdf/turtlebot3_waffle.urdf"
robot_description_config = Command(['xacro ', xacro_file, ' use_ros2_control:=', use_ros2_control, ' use_sim:=', use_sim_time]) robot_description_config = Command(['xacro ', xacro_file, ' use_ros2_control:=', use_ros2_control, ' use_sim:=', use_sim_time])
twist_mux_params = os.path.join( twist_mux_params = os.path.join(

View File

@ -4,8 +4,6 @@ import tf2_ros
import geometry_msgs.msg as gm import geometry_msgs.msg as gm
class TF2PublisherNode(Node): class TF2PublisherNode(Node):
def __init__(self): def __init__(self):

View File

@ -20,7 +20,7 @@ def generate_launch_description():
get_package_share_directory('slam_toolbox'),'launch','online_async_launch.py' get_package_share_directory('slam_toolbox'),'launch','online_async_launch.py'
)]), )]),
launch_arguments={ launch_arguments={
'use_sim_time': 'true', 'use_sim_time': 'false',
'slam_params_file': slam_params}.items() 'slam_params_file': slam_params}.items()
) )

View File

@ -14,7 +14,7 @@
#include "wheel.h" #include "wheel.h"
#include "arduino_comms.h" #include "arduino_comms.h"
using hardware_interface::CallbackReturn; // using hardware_interface::CallbackReturn;
using hardware_interface::return_type; using hardware_interface::return_type;
namespace diffdrive_arduino namespace diffdrive_arduino
@ -37,9 +37,11 @@ public:
CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override; CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override; // return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override;
return_type read() override;
return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) override; // return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) override;
return_type write() override;

View File

@ -13,7 +13,7 @@
#include "config.h" #include "config.h"
#include "wheel.h" #include "wheel.h"
using hardware_interface::CallbackReturn; //using CallbackReturn;
using hardware_interface::return_type; using hardware_interface::return_type;
class FakeRobot : public hardware_interface::SystemInterface class FakeRobot : public hardware_interface::SystemInterface
@ -33,9 +33,11 @@ public:
CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override; CallbackReturn on_deactivate(const rclcpp_lifecycle::State & previous_state) override;
return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override; // return_type read(const rclcpp::Time & time, const rclcpp::Duration & period) override;
return_type read() override;
return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) override; // return_type write(const rclcpp::Time & time, const rclcpp::Duration & period) override;
return_type write() override;
private: private:

View File

@ -14,7 +14,6 @@ void ArduinoComms::setup(const std::string &serial_device, int32_t baud_rate, in
serial::Timeout tt = serial::Timeout::simpleTimeout(timeout_ms); serial::Timeout tt = serial::Timeout::simpleTimeout(timeout_ms);
serial_conn_.setTimeout(tt); // This should be inline except setTimeout takes a reference and so needs a variable serial_conn_.setTimeout(tt); // This should be inline except setTimeout takes a reference and so needs a variable
serial_conn_.open(); serial_conn_.open();
} }
void ArduinoComms::sendEmptyMsg() void ArduinoComms::sendEmptyMsg()

View File

@ -95,7 +95,7 @@ CallbackReturn DiffDriveArduino::on_deactivate(const rclcpp_lifecycle::State & /
return CallbackReturn::SUCCESS; return CallbackReturn::SUCCESS;
} }
return_type DiffDriveArduino::read(const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */) return_type DiffDriveArduino::read()
{ {
// TODO fix chrono duration // TODO fix chrono duration
@ -123,7 +123,7 @@ return_type DiffDriveArduino::read(const rclcpp::Time & /* time */, const rclcpp
return return_type::OK; return return_type::OK;
} }
return_type DiffDriveArduino::write(const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */) return_type DiffDriveArduino::write()
{ {
if (!arduino_.connected()) if (!arduino_.connected())
{ {

View File

@ -4,6 +4,7 @@
int main(int argc, char **argv) int main(int argc, char **argv)
{ {
RCLCPP_INFO(logger_, "STARTING FILE");
ros::init(argc, argv, "diffdrive_robot"); ros::init(argc, argv, "diffdrive_robot");
ros::NodeHandle n("~"); ros::NodeHandle n("~");
@ -17,9 +18,11 @@ int main(int argc, char **argv)
n.getParam("enc_counts_per_rev", robot_cfg.enc_counts_per_rev); n.getParam("enc_counts_per_rev", robot_cfg.enc_counts_per_rev);
n.getParam("robot_loop_rate", robot_cfg.loop_rate); n.getParam("robot_loop_rate", robot_cfg.loop_rate);
RCLCPP_INFO(logger_, "STARTING DIFFDRIVE");
DiffDriveArduino robot(robot_cfg); DiffDriveArduino robot(robot_cfg);
RCLCPP_INFO(logger_, "FINISHED DIFFDRIVE");
controller_manager::ControllerManager cm(&robot); controller_manager::ControllerManager cm(&robot);
RCLCPP_INFO(logger_, "FINISHED CONTROLLER");
ros::AsyncSpinner spinner(1); ros::AsyncSpinner spinner(1);
spinner.start(); spinner.start();
@ -30,6 +33,7 @@ int main(int argc, char **argv)
while (ros::ok()) while (ros::ok())
{ {
RCLCPP_INFO(logger_, "Entered robot read/write loop.");
robot.read(); robot.read();
cm.update(robot.get_time(), robot.get_period()); cm.update(robot.get_time(), robot.get_period());
robot.write(); robot.write();

View File

@ -14,7 +14,7 @@ CallbackReturn FakeRobot::on_init(const hardware_interface::HardwareInfo & info)
return CallbackReturn::ERROR; return CallbackReturn::ERROR;
} }
RCLCPP_INFO(logger_, "Configuring..."); RCLCPP_INFO(logger_, "Configuring Fakerobot...");
time_ = std::chrono::system_clock::now(); time_ = std::chrono::system_clock::now();
@ -29,7 +29,7 @@ CallbackReturn FakeRobot::on_init(const hardware_interface::HardwareInfo & info)
l_wheel_.setup(cfg_.left_wheel_name); l_wheel_.setup(cfg_.left_wheel_name);
r_wheel_.setup(cfg_.right_wheel_name); r_wheel_.setup(cfg_.right_wheel_name);
RCLCPP_INFO(logger_, "Finished Configuration"); RCLCPP_INFO(logger_, "Finished Configuration Fakerobot");
return CallbackReturn::SUCCESS; return CallbackReturn::SUCCESS;
} }
@ -62,7 +62,8 @@ std::vector<hardware_interface::CommandInterface> FakeRobot::export_command_inte
hardware_interface::return_type FakeRobot::read(const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */) // hardware_interface::return_type FakeRobot::read(const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */)
hardware_interface::return_type FakeRobot::read()
{ {
// TODO fix chrono duration // TODO fix chrono duration
@ -83,7 +84,8 @@ hardware_interface::return_type FakeRobot::read(const rclcpp::Time & /* time */,
} }
hardware_interface::return_type FakeRobot::write(const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */) // hardware_interface::return_type FakeRobot::write(const rclcpp::Time & /* time */, const rclcpp::Duration & /* period */)
hardware_interface::return_type FakeRobot::write()
{ {
// Set the wheel velocities to directly match what is commanded // Set the wheel velocities to directly match what is commanded

1
src/xacro Submodule

@ -0,0 +1 @@
Subproject commit 344e25b49f3a01a2389f0f30304ed667d68a82bd