View generated_points.txt
0.0 0.0 0.0 | |
1.0 0.0 0.0 | |
2.0 0.0 0.0 | |
3.0 0.0 0.0 | |
4.0 0.0 0.0 | |
5.0 0.0 0.0 | |
6.0 0.0 0.0 | |
7.0 0.0 0.0 | |
8.0 0.0 0.0 | |
9.0 0.0 0.0 |
View from_drive_path_2_move_base_flex.py
#! /usr/bin/python | |
# credit Matt Droter | |
import rospy | |
import actionlib | |
from nav_msgs.msg import Path, Odometry | |
from geometry_msgs.msg import PoseStamped, Pose | |
from tf.transformations import quaternion_from_euler | |
from math import pow, atan2, sqrt |
View nmea_serial_driver.launch
<launch> | |
<!-- A simple launch file for the nmea_serial_driver node. --> | |
<arg name="port" default="/dev/gps" /> | |
<arg name="baud" default="115200" /> | |
<arg name="frame_id" default="gps" /> | |
<arg name="use_GNSS_time" default="False" /> | |
<arg name="time_ref_source" default="gps" /> | |
<arg name="useRMC" default="False" /> |
View teensy_launch.launch
<launch> | |
<?ignore - used to comment out lines | |
# taking out the potentiometer because I will first use the joystick connected to the laptop as well as command line cmd_vel statements | |
<node ns="potentiometer_teensy" name="potentiometer_output" pkg="rosserial_python" type="serial_node.py" args="/dev/potentiometer_control" output="screen" /> | |
Intial Steer Settings: | |
steer_left_max = 28900; | |
steer_right_max = 46300; | |
steer_straight = 36500; | |
max_steer_eff = 50; |
View gps_odom.py
#!/usr/bin/env python | |
# gps_odom.py credit Matt Droter | |
import rospy | |
import tf | |
import math | |
from nav_msgs.msg import Odometry | |
from tf.transformations import euler_from_quaternion, quaternion_from_euler, quaternion_multiply | |
from geometry_msgs.msg import Transform, Quaternion, QuaternionStamped, Pose, Point | |
from sensor_msgs.msg import NavSatFix, NavSatStatus, TimeReference |
View lawn_tractor.urdf.xacro
<?xml version="1.0"?> | |
<robot name="lawn_tractor" xmlns:xacro='http://www.ros.org/wiki/xacro'> | |
<!-- TODO: collision link element to be added --> | |
<!-- TODO: inertial link element to be added --> | |
<!-- define base link, center of rear axle for an ackermann vehicle --> | |
<link name="base_link"> | |
<visual> | |
<origin xyz='0.55 0 0' rpy='0 0 ${pi}' /> |
View lawn_tractor_sim_real_world.launch
<!-- file: robot_in_stage.launch --> | |
<launch> | |
<!-- ************** Global Parameters *************** --> | |
<param name="/use_sim_time" value="false"/> | |
<!-- ************** Stage Simulator *************** --> | |
<!-- ************** Robot Description *************** --> | |
<!-- robot_description is used by nodes that publish to joint_states. --> | |
<param name="robot_description" |
View ros_start_up.py
#!/usr/bin/env python | |
# modelled after: https://raw.githubusercontent.com/ablarry91/quadcopter_IR_control/e782f49390d5527ed86678acda727f5d698c0c07/monocular_pose_estimator/src/Tkinter_GUI.py | |
# inspired by: https://raw.githubusercontent.com/mturktest123/rosGUI/master/ROS_GUI.py | |
import subprocess | |
import time | |
from Tkinter import * | |
import rospy | |
from std_msgs.msg import Int16 | |
from sensor_msgs.msg import NavSatFix, NavSatStatus, TimeReference |
View parser.py
# Software License Agreement (BSD License) | |
# | |
# Copyright (c) 2013, Eric Perko | |
# All rights reserved. | |
# | |
# Redistribution and use in source and binary forms, with or without | |
# modification, are permitted provided that the following conditions | |
# are met: | |
# | |
# * Redistributions of source code must retain the above copyright |
View transmission_v1.cpp
/* | |
This program is designed to run on a Teensy that is connected to a SuperServo to make the Super Servo ROS enabled and control | |
the transmission of a lawn tractor. It is started in a launch file as one of multiple nodes with the command: | |
<node ns="transmission_teensy" name="transmission_cntrl" pkg="rosserial_python" type="serial_node.py" args="/dev/transmission_control" output="screen" /> | |
Overview: | |
subscribe to a target speed in cmd_vel format (i.e. cmd_vel.linear.x) | |
subscribe to actual speed from the rear wheels | |
adjust servo position to match actual speed to target speed |
NewerOlder