Skip to content

Commit

Permalink
fix the python tests
Browse files Browse the repository at this point in the history
Signed-off-by: M. Fatih Cırıt <mfc@leodrive.ai>
  • Loading branch information
M. Fatih Cırıt committed May 18, 2023
1 parent 2871fae commit cf5cbd9
Show file tree
Hide file tree
Showing 5 changed files with 17 additions and 18 deletions.
2 changes: 1 addition & 1 deletion control/vehicle_cmd_gate/script/delays_checker.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
# See the License for the specific language governing permissions and
# limitations under the License.

from autoware_auto_control_msgs.msg import Control
from autoware_control_msgs.msg import Control
from autoware_auto_vehicle_msgs.msg import Engage
from geometry_msgs.msg import AccelWithCovarianceStamped
from nav_msgs.msg import Odometry
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

import time

from autoware_auto_control_msgs.msg import Control
from autoware_control_msgs.msg import Control
from autoware_auto_planning_msgs.msg import Path
from autoware_auto_planning_msgs.msg import PathWithLaneId
from autoware_auto_planning_msgs.msg import Trajectory
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
from autoware_auto_control_msgs.msg import Control
from autoware_auto_control_msgs.msg import Lateral
from autoware_auto_control_msgs.msg import LongitudinalCommand
from autoware_control_msgs.msg import Control
from autoware_control_msgs.msg import Lateral
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSDurabilityPolicy
Expand Down Expand Up @@ -29,7 +28,7 @@ def publish_msg(self, control_cmd):
stamp = self.get_clock().now().to_msg()
msg = Control()
lateral_cmd = Lateral()
longitudinal_cmd = LongitudinalCommand()
longitudinal_cmd = Longitudinal()
lateral_cmd.stamp.sec = stamp.sec
lateral_cmd.stamp.nanosec = stamp.nanosec
lateral_cmd.steering_tire_angle = control_cmd["lateral"]["steering_tire_angle"]
Expand All @@ -38,7 +37,7 @@ def publish_msg(self, control_cmd):
]
longitudinal_cmd.stamp.sec = stamp.sec
longitudinal_cmd.stamp.nanosec = stamp.nanosec
longitudinal_cmd.velocity = control_cmd["longitudinal"]["speed"]
longitudinal_cmd.speed = control_cmd["longitudinal"]["speed"]
longitudinal_cmd.acceleration = control_cmd["longitudinal"]["acceleration"]
longitudinal_cmd.jerk = control_cmd["longitudinal"]["jerk"]

Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
import time

from autoware_auto_control_msgs.msg import Control
from autoware_auto_control_msgs.msg import Lateral
from autoware_auto_control_msgs.msg import LongitudinalCommand
from autoware_control_msgs.msg import Control
from autoware_control_msgs.msg import Lateral
from autoware_control_msgs.msg import Longitudinal
import pytest
import rclpy
from rclpy.executors import MultiThreadedExecutor
Expand Down Expand Up @@ -71,7 +71,7 @@ def generate_control_msg(self, control_cmd):
stamp = self.node.get_clock().now().to_msg()
msg = Control()
lateral_cmd = Lateral()
longitudinal_cmd = LongitudinalCommand()
longitudinal_cmd = Longitudinal()
lateral_cmd.stamp.sec = stamp.sec
lateral_cmd.stamp.nanosec = stamp.nanosec
lateral_cmd.steering_tire_angle = control_cmd["lateral"]["steering_tire_angle"]
Expand All @@ -80,7 +80,7 @@ def generate_control_msg(self, control_cmd):
]
longitudinal_cmd.stamp.sec = stamp.sec
longitudinal_cmd.stamp.nanosec = stamp.nanosec
longitudinal_cmd.velocity = control_cmd["longitudinal"]["speed"]
longitudinal_cmd.speed = control_cmd["longitudinal"]["speed"]
longitudinal_cmd.acceleration = control_cmd["longitudinal"]["acceleration"]
longitudinal_cmd.jerk = control_cmd["longitudinal"]["jerk"]

Expand All @@ -99,7 +99,7 @@ def set_speed(self, speed):
if len(self.msgs_rx) > 2:
break
received = self.msgs_rx[-1]
assert received.longitudinal.velocity == speed
assert received.longitudinal.speed == speed
self.msgs_rx.clear()

def set_acceleration(self, acceleration):
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
import time

from autoware_auto_control_msgs.msg import Control
from autoware_auto_control_msgs.msg import Lateral
from autoware_auto_control_msgs.msg import LongitudinalCommand
from autoware_control_msgs.msg import Control
from autoware_control_msgs.msg import Lateral
from autoware_control_msgs.msg import Longitudinal
import pytest
import rclpy
from rclpy.executors import MultiThreadedExecutor
Expand Down Expand Up @@ -70,7 +70,7 @@ def generate_control_msg(self, control_cmd):
stamp = self.node.get_clock().now().to_msg()
msg = Control()
lateral_cmd = Lateral()
longitudinal_cmd = LongitudinalCommand()
longitudinal_cmd = Longitudinal()
lateral_cmd.stamp.sec = stamp.sec
lateral_cmd.stamp.nanosec = stamp.nanosec
lateral_cmd.steering_tire_angle = control_cmd["lateral"]["steering_tire_angle"]
Expand All @@ -79,7 +79,7 @@ def generate_control_msg(self, control_cmd):
]
longitudinal_cmd.stamp.sec = stamp.sec
longitudinal_cmd.stamp.nanosec = stamp.nanosec
longitudinal_cmd.velocity = control_cmd["longitudinal"]["speed"]
longitudinal_cmd.speed = control_cmd["longitudinal"]["speed"]
longitudinal_cmd.acceleration = control_cmd["longitudinal"]["acceleration"]
longitudinal_cmd.jerk = control_cmd["longitudinal"]["jerk"]

Expand Down

0 comments on commit cf5cbd9

Please sign in to comment.