Skip to content

Stm #5

Open
wants to merge 55 commits into
base: develop
Choose a base branch
from
Open

Stm #5

wants to merge 55 commits into from

Conversation

kshpv
Copy link
Member

@kshpv kshpv commented Dec 19, 2018

Misha, please, pull my beautiful code again 😀😀😀

@MisterMap
Copy link
Collaborator

Stm must be written as STM

import itertools
from STM_protocol import STMprotocol

ODOM_RATE = 40 # Hz
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

move this constant to config yaml file

# Init ROS
rospy.init_node('stm_node', anonymous=True)
# ROS subscribers
rospy.Subscriber("stm_command", String, self.stm_command_callback)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Initialize subscriber in the end of init function

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

May be race condition

super(STMnode, self).__init__(serial_port, baudrate)
self.mutex = Lock()

self.laser_coords = (rospy.get_param('lidar_x') / 1000.0, rospy.get_param('lidar_y') / 1000.0, 0.41)
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Change config file to make all constant in meters


rospy.Timer(rospy.Duration(1. / ODOM_RATE), self.odom_callback)

def stm_command_callback(self, data):
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why you remove cmd_id ?

rospy.loginfo('Got response args: '+ str(values))
return successfully, values

def odom_callback(self, event):
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

odom callback?

successfully, values = self.send(0x0F, args=None)
if successfully:
self.send_odometry(values)

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Make twist_callback

t.header.stamp = rospy.Time.now()
t.header.frame_id = "secondary_robot_odom"
t.child_frame_id = "secondary_robot"
t.transform.translation.x = values[0]
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Use function from core function to cvt_ros_transform2point

if successfully:
self.send_odometry(values)

def send_odometry(self, values):
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

rename to publish_odometry


self.tf2_broad.sendTransform(t)

t = geometry_msgs.msg.TransformStamped()
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Make function publish_tf


t = geometry_msgs.msg.TransformStamped()
t.header.stamp = rospy.Time.now()
t.header.frame_id = "secondary_robot"
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Make this as params in config file

import struct
import serial
import itertools
from STM_protocol import STMprotocol

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

test

Copy link
Collaborator

@MisterMap MisterMap left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Add launch file for stm node

@MisterMap MisterMap changed the base branch from master to develop March 5, 2019 15:10
Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants