mirror of
https://github.com/6-robot/wpr_simulation2.git
synced 2025-09-15 12:58:54 +08:00
add demo_4
This commit is contained in:
parent
cd35a30bf4
commit
0e94a37c5e
@ -48,6 +48,11 @@ ament_target_dependencies(3_subscriber_node
|
||||
"rclcpp" "std_msgs"
|
||||
)
|
||||
|
||||
add_executable(4_velocity_command demo_cpp/4_velocity_command.cpp)
|
||||
ament_target_dependencies(4_velocity_command
|
||||
"rclcpp" "geometry_msgs"
|
||||
)
|
||||
|
||||
add_executable(demo_mani_ctrl demo_cpp/demo_mani_ctrl.cpp)
|
||||
ament_target_dependencies(demo_mani_ctrl
|
||||
"rclcpp" "sensor_msgs"
|
||||
@ -77,6 +82,7 @@ install(
|
||||
TARGETS
|
||||
wpb_home_mani_sim
|
||||
3_publisher_node 3_subscriber_node
|
||||
4_velocity_command
|
||||
demo_mani_ctrl
|
||||
demo_nav2_client
|
||||
DESTINATION
|
||||
|
||||
29
demo_cpp/4_velocity_command.cpp
Normal file
29
demo_cpp/4_velocity_command.cpp
Normal file
@ -0,0 +1,29 @@
|
||||
#include <rclcpp/rclcpp.hpp>
|
||||
#include <geometry_msgs/msg/twist.hpp>
|
||||
|
||||
int main(int argc, char** argv)
|
||||
{
|
||||
rclcpp::init(argc, argv);
|
||||
auto node = std::make_shared<rclcpp::Node>("velocity_command_node");
|
||||
|
||||
auto vel_pub = node->create_publisher<geometry_msgs::msg::Twist>("/cmd_vel", 10);
|
||||
|
||||
geometry_msgs::msg::Twist vel_msg;
|
||||
vel_msg.linear.x = 0.1;
|
||||
vel_msg.linear.y = 0.0;
|
||||
vel_msg.linear.z = 0.0;
|
||||
vel_msg.angular.x = 0.0;
|
||||
vel_msg.angular.y = 0.0;
|
||||
vel_msg.angular.z = 0.0;
|
||||
|
||||
rclcpp::Rate loop_rate(30);
|
||||
while (rclcpp::ok())
|
||||
{
|
||||
vel_pub->publish(vel_msg);
|
||||
loop_rate.sleep();
|
||||
}
|
||||
|
||||
rclcpp::shutdown();
|
||||
|
||||
return 0;
|
||||
}
|
||||
@ -52,7 +52,7 @@ def generate_launch_description():
|
||||
# Launch configuration variables specific to simulation
|
||||
pose_x = LaunchConfiguration('pose_x', default='0.0')
|
||||
pose_y = LaunchConfiguration('pose_y', default='0.0')
|
||||
pose_y = LaunchConfiguration('pose_theta', default='0.0')
|
||||
pose_theta = LaunchConfiguration('pose_theta', default='0.0')
|
||||
|
||||
# Declare the launch arguments
|
||||
declare_x_position_cmd = DeclareLaunchArgument(
|
||||
|
||||
@ -55,7 +55,7 @@ def generate_launch_description():
|
||||
# Launch configuration variables specific to simulation
|
||||
pose_x = LaunchConfiguration('pose_x', default='0.0')
|
||||
pose_y = LaunchConfiguration('pose_y', default='0.0')
|
||||
pose_y = LaunchConfiguration('pose_theta', default='0.0')
|
||||
pose_theta = LaunchConfiguration('pose_theta', default='0.0')
|
||||
|
||||
# Declare the launch arguments
|
||||
declare_x_position_cmd = DeclareLaunchArgument(
|
||||
|
||||
Loading…
Reference in New Issue
Block a user