Removed unused files.
Removed old, inactive code. Added a brief description to joy.py and handle_nan_scan.py explaining their purpose. speed.py is not used anymore but referenced in the final report, so I added a note explaining that.
This commit is contained in:
parent
cefe2d0f61
commit
cb0c854869
@ -6,7 +6,10 @@ import geometry_msgs.msg as gm
|
||||
|
||||
|
||||
class TF2PublisherNode(Node):
|
||||
|
||||
""" The purpose of this node is to modify the LaserScan produced by velodyne so as to be compatible with slam_toolbox.
|
||||
It seems there is an off-by-one error in slam_toolbox calculating the number of expected points in the scan,
|
||||
resulting in warnings that /scan contains fewer points than expected.
|
||||
"""
|
||||
def __init__(self):
|
||||
super().__init__('nanhandler')
|
||||
|
||||
@ -20,9 +23,6 @@ class TF2PublisherNode(Node):
|
||||
|
||||
msg.ranges.append(float("inf"))
|
||||
msg.intensities.append(0.0)
|
||||
# ranges = np.array(msg.ranges)
|
||||
# mask_inf_dist = np.isinf(ranges)
|
||||
# print(np.array(msg.intensities)[mask_inf_dist])
|
||||
|
||||
self.pub.publish(msg)
|
||||
|
||||
|
@ -101,7 +101,6 @@ class Joystick(object):
|
||||
# since we're using ID's as indices, account for 0 based indices
|
||||
self.__button_values = [0] * (JSEvent.MAX_BUTTON_COUNT + 1)
|
||||
|
||||
# TODO: think about adding in previous value lists
|
||||
self.update_id = -1
|
||||
self.AxisUpdate = False
|
||||
self.ButtonUpdate = False
|
||||
@ -152,8 +151,6 @@ class JoystickController(Joystick):
|
||||
self.direction_vector = (0, 0)
|
||||
# rotation tells the robot to rotate x degrees
|
||||
self.rotation_vector = (0, 0)
|
||||
# rotation as direction - rotation
|
||||
# self.difference_vector = (0, 0)
|
||||
|
||||
def hasUpdate(self):
|
||||
return self.ButtonUpdate or self.AxisUpdate
|
||||
|
@ -1,65 +0,0 @@
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
|
||||
from geometry_msgs.msg import Twist
|
||||
from std_msgs.msg import String
|
||||
from nav_msgs.msg import Odometry
|
||||
|
||||
import numpy as np
|
||||
|
||||
|
||||
SCALE_FACTOR = 1.0
|
||||
|
||||
|
||||
|
||||
class TwistPublisher(Node):
|
||||
def __init__(
|
||||
self,
|
||||
scale_factor=20.0
|
||||
):
|
||||
super().__init__("twist_publisher")
|
||||
|
||||
self.scale_factor = scale_factor
|
||||
|
||||
self.publisher_ = self.create_publisher(
|
||||
Odometry, "/odom_scaled", 1
|
||||
)
|
||||
|
||||
self.create_subscription(Odometry, "/odom", self.odom_callback, 1)
|
||||
|
||||
def odom_callback(self, odom_message:Odometry):
|
||||
odom_message.twist.twist.linear.x *= self.scale_factor
|
||||
odom_message.twist.twist.linear.y *= self.scale_factor
|
||||
odom_message.twist.twist.linear.z *= self.scale_factor
|
||||
odom_message.twist.twist.angular.x *= self.scale_factor
|
||||
odom_message.twist.twist.angular.y *= self.scale_factor
|
||||
odom_message.twist.twist.angular.z *= self.scale_factor
|
||||
odom_message.pose.pose.position.x *= self.scale_factor
|
||||
odom_message.pose.pose.position.y *= self.scale_factor
|
||||
odom_message.pose.pose.position.z *= self.scale_factor
|
||||
odom_message.pose.pose.orientation.x *= self.scale_factor
|
||||
odom_message.pose.pose.orientation.y *= self.scale_factor
|
||||
odom_message.pose.pose.orientation.z *= self.scale_factor
|
||||
|
||||
self.publisher_.publish(odom_message)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
|
||||
minimal_publisher = TwistPublisher(
|
||||
SCALE_FACTOR
|
||||
)
|
||||
|
||||
rclpy.spin(minimal_publisher)
|
||||
|
||||
minimal_publisher.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
@ -1,3 +1,9 @@
|
||||
"""
|
||||
This file is not required anymore. It was our first, naive approach to translate Joy messages to track speeds for the robot.
|
||||
It is referenced in the project report, which is why we decided to keep it in the repo.
|
||||
"""
|
||||
|
||||
|
||||
import math
|
||||
from typing import List
|
||||
|
||||
|
@ -1,55 +0,0 @@
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
import tf2_ros
|
||||
import geometry_msgs.msg as gm
|
||||
|
||||
|
||||
class TF2PublisherNode(Node):
|
||||
|
||||
def __init__(self):
|
||||
super().__init__('tf2_publisher_node')
|
||||
self.tf_broadcaster = tf2_ros.TransformBroadcaster(self)
|
||||
|
||||
self.timer = self.create_timer(0.1, self.publish_identity_transform)
|
||||
|
||||
def send_parent_child_identity_tf(self, parent, child):
|
||||
transform_stamped = gm.TransformStamped()
|
||||
transform_stamped.header.stamp = self.get_clock().now().to_msg()
|
||||
transform_stamped.header.frame_id = parent
|
||||
transform_stamped.child_frame_id = child
|
||||
|
||||
# Identity transform (no translation, no rotation)
|
||||
transform_stamped.transform.translation.x = 0.0
|
||||
transform_stamped.transform.translation.y = 0.0
|
||||
transform_stamped.transform.translation.z = 0.0
|
||||
transform_stamped.transform.rotation.x = 0.0
|
||||
transform_stamped.transform.rotation.y = 0.0
|
||||
transform_stamped.transform.rotation.z = 0.0
|
||||
transform_stamped.transform.rotation.w = 1.0
|
||||
|
||||
self.tf_broadcaster.sendTransform(transform_stamped)
|
||||
|
||||
|
||||
def publish_identity_transform(self):
|
||||
# self.send_parent_child_identity_tf("map", "odom")
|
||||
# self.send_parent_child_identity_tf("odom", "base_link")
|
||||
# self.send_parent_child_identity_tf("base_link", "base_scan")
|
||||
# self.send_parent_child_identity_tf("base_scan", "velodyne")
|
||||
self.send_parent_child_identity_tf("base_link", "velodyne")
|
||||
self.send_parent_child_identity_tf("base_link", "base_footprint")
|
||||
|
||||
|
||||
self.get_logger().info('Published identity transform')
|
||||
|
||||
def main(args=None):
|
||||
rclpy.init(args=args)
|
||||
|
||||
tf2_publisher = TF2PublisherNode()
|
||||
rclpy.spin(tf2_publisher)
|
||||
|
||||
tf2_publisher.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
main()
|
@ -15,6 +15,10 @@ SMOOTH_WEIGHTS = np.array([1, 2, 4, 10, 20])
|
||||
|
||||
|
||||
class TwistPublisher(Node):
|
||||
"""
|
||||
This node serves as a bridge between the Joy messages published from the PS3 controller
|
||||
interface in joy.py and the Twist messages expected by ros_control.
|
||||
"""
|
||||
def __init__(
|
||||
self,
|
||||
smooth_weights=np.ones(5),
|
||||
@ -40,10 +44,6 @@ class TwistPublisher(Node):
|
||||
self.linear_scale = linear_scale
|
||||
self.angular_scale = angular_scale
|
||||
|
||||
# self.publisher_ = self.create_publisher(
|
||||
# Twist, "/diff_cont/cmd_vel_unstamped", 1
|
||||
# )
|
||||
|
||||
self.publisher_2 = self.create_publisher(Twist, "/cmd_vel_joystick", 1)
|
||||
|
||||
self.create_subscription(Joy, "/joy", self.joy_callback, 1)
|
||||
@ -83,16 +83,7 @@ class TwistPublisher(Node):
|
||||
|
||||
msg.linear.x = self.linear_out
|
||||
msg.angular.z = self.angular_out
|
||||
# self.publisher_.publish(msg)
|
||||
self.publisher_2.publish(msg)
|
||||
# self.get_logger().info(
|
||||
# "Linear_window: {}, Linear_out: {}, Angular_window: {}, Angular_out: {}".format(
|
||||
# self.linear_window,
|
||||
# self.linear_out,
|
||||
# self.angular_window,
|
||||
# self.angular_out,
|
||||
# )
|
||||
# )
|
||||
|
||||
|
||||
def main(args=None):
|
||||
|
Loading…
x
Reference in New Issue
Block a user