modify rover_self_drving

This commit is contained in:
Your Name 2020-12-14 19:22:34 +08:00
parent e448f0ba1d
commit b14c687533
4 changed files with 8 additions and 20 deletions

View File

@ -92,23 +92,13 @@ class Communication:
target_raw_pose = PositionTarget()
target_raw_pose.coordinate_frame = self.coordinate_frame
if self.coordinate_frame == 1:
target_raw_pose.position.x = x
target_raw_pose.position.y = y
target_raw_pose.position.z = z
target_raw_pose.position.x = x
target_raw_pose.position.y = y
target_raw_pose.position.z = z
target_raw_pose.velocity.x = vx
target_raw_pose.velocity.y = vy
target_raw_pose.velocity.z = vz
else:
target_raw_pose.position.x = -y
target_raw_pose.position.y = x
target_raw_pose.position.z = z
target_raw_pose.velocity.x = -vy
target_raw_pose.velocity.y = vx
target_raw_pose.velocity.z = vz
target_raw_pose.velocity.x = vx
target_raw_pose.velocity.y = vy
target_raw_pose.velocity.z = vz
target_raw_pose.yaw = yaw

View File

@ -3,7 +3,7 @@ from geometry_msgs.msg import Twist
from std_msgs.msg import Int16
Kp = 0.003
Vx = 3
Vx = 5
def lane_mid_error_callback(msg):
global twist
@ -16,7 +16,7 @@ def lane_mid_error_callback(msg):
else:
twist.linear.y = 0.0
twist.linear.x = Vx * (1 - twist.linear.x)
twist.linear.x = Vx * (1 - abs(twist.linear.y))
if __name__ == "__main__":

Binary file not shown.

Before

Width:  |  Height:  |  Size: 978 KiB

After

Width:  |  Height:  |  Size: 1.0 MiB

View File

@ -1,6 +1,4 @@
import numpy as np
import sys
sys.path.remove('/opt/ros/kinetic/lib/python2.7/dist-packages')
import cv2
import math
import rospy