Skip to content

Commit a2f7da1

Browse files
committed
fix for coordinate nodes
1 parent 6aebfbc commit a2f7da1

File tree

3 files changed

+18
-9
lines changed

3 files changed

+18
-9
lines changed

uwrt_mars_rover_utils/uwrt_mars_rover_xbox_controller/launch/location_launch.py

Lines changed: 7 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,12 @@
1+
import os
12
import launch
23
from launch import LaunchDescription
3-
from launch_ros.actions import Node
4-
from launch_ros.descriptions import ComposableNode
4+
from launch.actions import SetEnvironmentVariable
55
from launch_ros.actions import ComposableNodeContainer
6+
from launch_ros.descriptions import ComposableNode
67

78
def generate_launch_description():
9+
810
container = ComposableNodeContainer(
911
name='container',
1012
namespace="",
@@ -16,7 +18,8 @@ def generate_launch_description():
1618
plugin='drivetraincontrollerComposition::CoordinateNode',
1719
name='coordinateNode'
1820
),
19-
]
21+
],
22+
output='screen'
2023
)
24+
2125
return launch.LaunchDescription([container])
22-

uwrt_mars_rover_utils/uwrt_mars_rover_xbox_controller/src/coordinateNode.cpp

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -5,11 +5,17 @@ namespace drivetraincontrollerComposition
55
CoordinateNode::CoordinateNode(const rclcpp::NodeOptions & options) : Node("coordinateNode", options) {
66
auto callback = [this](const uwrt_mars_rover_xbox_controller::msg::XboxController::SharedPtr msg_in) -> void {
77
//Add scaling value
8-
const int vConstant = 5;
8+
int vConstant = 5;
99

1010
auto msg = std::make_unique<geometry_msgs::msg::Twist>();
11-
msg->linear.x = (*msg_in).drivetrain_joy_x * vConstant;
12-
msg->angular.z = (*msg_in).gimble_joy_x * vConstant;
11+
msg->linear.x = (*msg_in).drivetrain_joy_y * vConstant;
12+
msg->angular.z = (*msg_in).drivetrain_joy_x * vConstant;
13+
msg->linear.x = (*msg_in).gimble_joy_y*(vConstant++);
14+
msg->linear.x = (*msg_in).gimble_joy_x*(vConstant--);
15+
16+
//To avoid overflow
17+
if(vConstant > 2147483647 || vConstant < 0)
18+
vConstant = 5;
1319

1420
pub_->publish(std::move(msg));
1521
};
@@ -21,4 +27,4 @@ CoordinateNode::CoordinateNode(const rclcpp::NodeOptions & options) : Node("coor
2127
} // namespace drivetraincontrollerComposition
2228

2329
#include <rclcpp_components/register_node_macro.hpp>
24-
RCLCPP_COMPONENTS_REGISTER_NODE(drivetraincontrollerComposition::CoordinateNode)
30+
RCLCPP_COMPONENTS_REGISTER_NODE(drivetraincontrollerComposition::CoordinateNode)

uwrt_mars_rover_utils/uwrt_mars_rover_xbox_controller/src/uwrt_mars_rover_xbox_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@ UWRTXboxController::UWRTXboxController(const rclcpp::NodeOptions & options)
1212
"joy", 10, std::bind(&UWRTXboxController::getXboxData, this, std::placeholders::_1));
1313
xbox_node_pub = create_publisher<xbox_msg>("/xbox_info", 10);
1414
pub_timer =
15-
create_wall_timer(100ms, std::bind(&UWRTXboxController::publishStructuredXboxData, this));
15+
create_wall_timer(1000ms, std::bind(&UWRTXboxController::publishStructuredXboxData, this));
1616
}
1717

1818
void UWRTXboxController::getXboxData(const joy_msg::SharedPtr msg)

0 commit comments

Comments
 (0)