Skip to content

Commit

Permalink
add teleop exp
Browse files Browse the repository at this point in the history
  • Loading branch information
Cionix90 committed Oct 21, 2024
1 parent a52f0bf commit fe8078b
Show file tree
Hide file tree
Showing 3 changed files with 156 additions and 10 deletions.
22 changes: 13 additions & 9 deletions pronto_ros/include/pronto_ros/ros_frontend.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,9 @@ class ROSFrontEnd {
if (!subscribe) {
return;
}

rclcpp::QoS qos(10);
qos.reliability(rclcpp::ReliabilityPolicy::BestEffort);
qos.reliability(rclcpp::ReliabilityPolicy::Reliable);
RCLCPP_INFO_STREAM(nh_->get_logger(), sensor_id << " subscribing to " << topic
<< " with SecondaryMsgT = " << type_name<SecondaryMsgT>());
secondary_subscribers_[sensor_id] = nh_->create_subscription<SecondaryMsgT>(
Expand Down Expand Up @@ -119,15 +120,15 @@ class ROSFrontEnd {
}

template <class MsgT>
void initCallback(std::shared_ptr<MsgT const> msg,
void initCallback(std::shared_ptr<MsgT > msg,
const SensorId& Key);

template <class PrimaryMsgT, class SecondaryMsgT>
void secondaryCallback(std::shared_ptr<SecondaryMsgT const> msg,
void secondaryCallback(std::shared_ptr<SecondaryMsgT > msg,
const SensorId& sensor_id);

template <class MsgT>
void callback(std::shared_ptr<MsgT const> msg, const SensorId& Key);
void callback(std::shared_ptr<MsgT > msg, const SensorId& Key);

protected:
bool initializeFilter();
Expand Down Expand Up @@ -192,7 +193,7 @@ void ROSFrontEnd::addInitModule(SensingModule<MsgT>& module,
RCLCPP_INFO_STREAM(nh_->get_logger(), "Sensor init id: " << sensor_id);
RCLCPP_INFO_STREAM(nh_->get_logger(), "Topic: " << topic);
rclcpp::QoS qos(10);
qos.reliability(rclcpp::ReliabilityPolicy::BestEffort);
qos.reliability(rclcpp::ReliabilityPolicy::Reliable);
// add the sensor to the list of sensor that require initialization
std::pair<SensorId, bool> init_id_pair(sensor_id, false);
initialized_list_.insert(init_id_pair);
Expand Down Expand Up @@ -231,7 +232,7 @@ void ROSFrontEnd::addSensingModule(SensingModule<MsgT>& module,
RCLCPP_INFO_STREAM(nh_->get_logger(), "Publish head: " << (publish_head ? "yes" : "no"));
RCLCPP_INFO_STREAM(nh_->get_logger(), "Topic: " << topic);
rclcpp::QoS qos(10);
qos.reliability(rclcpp::ReliabilityPolicy::BestEffort);
qos.reliability(rclcpp::ReliabilityPolicy::Reliable);
// store the will to roll forward when the message is received
std::pair<SensorId, bool> roll_pair(sensor_id, roll_forward);
roll_forward_.insert(roll_pair);
Expand Down Expand Up @@ -259,13 +260,14 @@ void ROSFrontEnd::addSensingModule(SensingModule<MsgT>& module,


template <class MsgT>
void ROSFrontEnd::initCallback(std::shared_ptr<MsgT const> msg, const SensorId& sensor_id)
void ROSFrontEnd::initCallback(std::shared_ptr<MsgT> msg, const SensorId& sensor_id)
{
if(verbose_){
RCLCPP_INFO_STREAM(nh_->get_logger(), "Init callback for sensor " << sensor_id);
}
if(initialized_list_.count(sensor_id) > 0 && !initialized_list_[sensor_id])
{
msg->header.set__stamp(nh_->get_clock()->now());
initialized_list_[sensor_id] = static_cast<SensingModule<MsgT>*>(init_modules_[sensor_id])->processMessageInit(
msg.get(),
initialized_list_,
Expand Down Expand Up @@ -298,7 +300,7 @@ void ROSFrontEnd::initCallback(std::shared_ptr<MsgT const> msg, const SensorId&
#define DEBUG_MODE 0

template <class MsgT>
void ROSFrontEnd::callback(std::shared_ptr<MsgT const> msg, const SensorId& sensor_id)
void ROSFrontEnd::callback(std::shared_ptr<MsgT> msg, const SensorId& sensor_id)
{
#if DEBUG_MODE
RCLCPP_INFO_STREAM(nh_->get_logger(), "Callback for sensor " << sensor_id);
Expand All @@ -311,6 +313,7 @@ void ROSFrontEnd::callback(std::shared_ptr<MsgT const> msg, const SensorId& sens
// appropriate casting to the right type and call to the process message
// function to get the update
// Record start time
msg->header.set__stamp(nh_->get_clock()->now());
#if DEBUG_MODE
auto start = std::chrono::high_resolution_clock::now();
#endif
Expand Down Expand Up @@ -448,8 +451,9 @@ void ROSFrontEnd::callback(std::shared_ptr<MsgT const> msg, const SensorId& sens
}

template <class PrimaryMsgT, class SecondaryMsgT>
void ROSFrontEnd::secondaryCallback(std::shared_ptr<SecondaryMsgT const> msg, const SensorId& sensor_id)
void ROSFrontEnd::secondaryCallback(std::shared_ptr<SecondaryMsgT > msg, const SensorId& sensor_id)
{
msg->header.set__stamp(nh_->get_clock()->now());
auto a = dynamic_cast<DualSensingModule<PrimaryMsgT,SecondaryMsgT>*>(static_cast<SensingModule<PrimaryMsgT>*>(active_modules_[sensor_id]));
a->processSecondaryMessage(*msg);
}
Expand Down
2 changes: 1 addition & 1 deletion pronto_tuning/launch/omnicar_exp.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ def generate_launch_description():

exp_name_value = LaunchConfiguration("exp_name")
package_path = FindPackageShare("pronto_tuning")
exp_name_arg = DeclareLaunchArgument("exp_name",default_value="Exp_o_cmd.yaml")
exp_name_arg = DeclareLaunchArgument("exp_name",default_value="Exp_1_cmd.yaml")


#start qualisys
Expand Down
142 changes: 142 additions & 0 deletions pronto_tuning/launch/omnicar_exp_teleop.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,142 @@
import os

from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription,ExecuteProcess
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import LaunchConfiguration,PathJoinSubstitution,TextSubstitution
from ament_index_python.packages import get_package_share_path
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.actions import TimerAction
from launch.actions import DeclareLaunchArgument
import subprocess
from launch.actions import DeclareLaunchArgument,EmitEvent, RegisterEventHandler,ExecuteProcess
from launch.event_handlers import (OnExecutionComplete, OnProcessExit,
OnProcessIO, OnProcessStart, OnShutdown)
from datetime import datetime


def generate_launch_description():

exp_name_value = LaunchConfiguration("exp_name")
package_path = FindPackageShare("pronto_tuning")
exp_name_arg = DeclareLaunchArgument("exp_name",default_value="Exp_1_cmd.yaml")


#start qualisys
qualysis = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution([
FindPackageShare("qualisys_driver")
, 'launch', 'qualisys.launch.py'])
))

# qualysis = IncludeLaunchDescription(
# PythonLaunchDescriptionSource(
# PathJoinSubstitution([
# FindPackageShare("pronto_ros2_node")
# , 'launch', 'qualisys.launch.py'])
# ))

bag_base_path = "/home/ros/docker_pronto_ws/bags/"
#starts controller
IMU_Broadcaster_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["IMU_Broadcaster", "--controller-manager", "/controller_manager"],
)


ordered_IMU_Broadcaster_spawner = TimerAction(actions=[IMU_Broadcaster_spawner],period=1.0)

state_broadcaster_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["state_broadcaster", "--controller-manager", "/controller_manager"],
)

ordered_state_broadcaster_spawner = RegisterEventHandler(

OnProcessExit(target_action=IMU_Broadcaster_spawner, on_exit=[state_broadcaster_spawner])
)


omni_controller_spawner = Node(
package="controller_manager",
executable="spawner",
arguments=["omni_controller", "--controller-manager", "/controller_manager"],
)
ordered_omni_controller_spawner = RegisterEventHandler(

OnProcessExit(target_action=state_broadcaster_spawner, on_exit=[omni_controller_spawner])
)

rf2o_odom = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution([
FindPackageShare("rf2o")
, 'launch', 'rf2o_laser_odometry.launch.py'])
))
ordered_rf2o_odom = RegisterEventHandler(

OnProcessExit(target_action=IMU_Broadcaster_spawner, on_exit=[rf2o_odom])
)

#start bag
time = datetime.now()

time_str = time.strftime("%Y_%m_%d_%H_%M_%S")

bag_path = bag_base_path + "Exp_TeleOp" +time_str

start_bag = ExecuteProcess(
cmd=['ros2', 'bag', 'record','-a','-s','mcap', '-o', bag_path ],
output='screen'
)

command_launch = joy_node = Node(
package="omni_mulinex_joystic",
executable="omni_mul_joystic_node",
output="screen",
parameters=[
{"bag_folder": "/home/ros/docker_pronto_ws/"},
{"sup_vel_x": 0.5},
{"sup_vel_y": 0.5},
{"sup_omega": 1.0},
{"deadzone_joy": 0.1}
]
)

delayed_start_exp = TimerAction(
actions=[command_launch], period=5.0
)
delayed_start = TimerAction(
actions=[delayed_start_exp,start_bag], period=5.0
)



# ordered_command_launch = RegisterEventHandler(

# OnProcessExit(target_action=IMU_Broadcaster_spawner, on_exit=[command_launch])
# )


return LaunchDescription([
qualysis,
exp_name_arg,
ordered_omni_controller_spawner,
ordered_state_broadcaster_spawner,
ordered_IMU_Broadcaster_spawner,
ordered_rf2o_odom,
delayed_start,
Node(
package="joy",
executable="joy_node",
output="screen"
)
# ordered_start_bag
# ordered_command_launch
# start_bag
])

0 comments on commit fe8078b

Please sign in to comment.