Skip to content

Commit

Permalink
fix import errors in planner
Browse files Browse the repository at this point in the history
  • Loading branch information
jcrm1 committed Mar 2, 2024
1 parent 056114d commit 5088eac
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
8 changes: 4 additions & 4 deletions src/rktl_planner/rktl_planner/nodes/path_planner.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
import rclpy
import numpy as np
from rktl_dependencies.transformations import quaternion_from_euler, euler_from_quaternion
from std_msgs.msg import Duration
from rclpy.duration import Duration
from nav_msgs.msg import Odometry
from geometry_msgs.msg import Pose
from rktl_msgs.msg import BezierPathList, Path
Expand All @@ -25,7 +25,7 @@ def create_simple_path_req(car_odom, ball_odom, goal_pos):
pose0.position.z = 0.0
pose0.orientation = car_odom.pose.pose.orientation
req.target_poses.append(pose0)
req.target_durations.append(Duration(data=node.create_rate(5.0)))
req.target_durations.append(Duration(data=node.create_rate(5.0)).to_msg())

# Target 1 (ball pos)
final_vec_x = goal_pos[0] - ball_odom.pose.pose.position.x
Expand All @@ -42,7 +42,7 @@ def create_simple_path_req(car_odom, ball_odom, goal_pos):
pose1.orientation.z = final_quat[2]
pose1.orientation.w = final_quat[3]
req.target_poses.append(pose1)
req.target_durations.append(Duration(data=node.create_rate(1.0)))
req.target_durations.append(Duration(data=node.create_rate(1.0)).to_msg())

# Target 2 (stop)
pose2 = Pose()
Expand All @@ -67,7 +67,7 @@ def create_backup_path_req(car_odom, ball_odom, goal_pos):
pose0.position.z = 0.0
pose0.orientation = car_odom.pose.pose.orientation
req.target_poses.append(pose0)
req.target_durations.append(Duration(data=node.create_rate(1.0)))
req.target_durations.append(Duration(data=node.create_rate(1.0)).to_msg())

# Target 1 (in front of ball)
final_vec_x = goal_pos[0] - ball_odom.pose.pose.position.x
Expand Down
2 changes: 1 addition & 1 deletion src/rktl_planner/rktl_planner/pure_pursuit.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
# 3rd party modules
import numpy as np
import math
from rktl_dependencies.rktl_dependencies.transformations import euler_from_quaternion
from rktl_dependencies.transformations import euler_from_quaternion


def find_intersection(path_seg, bot_path, lookahead_dist):
Expand Down

0 comments on commit 5088eac

Please sign in to comment.