This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
/** | |
AS5048B_using_360_degrees_v2.cpp | |
The sensor will read and calculate the meters travelled at 10 Hz | |
m/s and RPM will be calculated each time a print is performed every 2 seconds (0.5 HZ) using meters travelled as input. | |
Therefore m/s and RPM will averaged for that 2 second period | |
*/ | |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
#!/usr/bin/env python | |
""" | |
Produces cmd_vel statements based on input entered into a text file in the format: | |
linear.x, angular.z, duration (seconds) | |
0.5, 0.0, 10 <---- 0.5 m/s, go straight for 10 seconds | |
1.5, 1.0, 15 <---- 1.5 m/s, full left? for 15 seconds | |
An example command to access one element of the table that is loaded: print(mission_commands[2][1]) # row 2, element 1 - remember 0 reference | |
The .txt file needs at least two entries otherwise you will get the error: IndexError: invalid index to scalar variable. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
/* | |
Program to track the absolute position of an AMS_AS5048B encoder since CPU reset even though the encoder rolls over the 14bit register 0-16348 that is built in. | |
In other words, the encoder can keep spinning and this program keeps track of the total rotations/distance travelled or however you want to represent | |
knowing the absolute position. The value of "ticks" will be stored in "rotational_position". | |
*/ | |
#include <Wire.h> | |
//unit consts |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
/* | |
front_angle_v6.cpp | |
Read the AMS-5048B angle sensor and publish the steering angle - front_angle_raw = the raw value of the sensor | |
This program will also read an analog potentiometer during setup to make sure the wheels are pointing straight. | |
The program will track the absolute position of an AMS_AS5048B encoder since CPU reset even though the encoder rolls over the 14bit register 0-16348 | |
that is built in. In other words, the encoder can keep spinning and this program keeps track of the total rotations/distance travelled or |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
#!/usr/bin/env python | |
""" | |
Produces cmd_vel statements based on input entered into a text file in the format: | |
linear.x, angular.z, distance (meters) | |
0.5, 0.0, 10 <---- 0.5 m/s, go straight for 10 meters | |
1.5, 1.0, 15 <---- 1.5 m/s, full left? for 15 meters | |
An example command to access one element of the table that is loaded: print(mission_commands[2][1]) # row 2, element 1 - remember 0 reference | |
The .txt file needs at least two entries otherwise you will get the error: IndexError: invalid index to scalar variable. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
/* | |
left_speed_sensor_v4.cpp | |
Reads AS5048B using a Teensy 3.2 and I2C communiction | |
This reads the sensor, calculates speed and distance travelled and publishes the values using ROS to output the data. | |
The frequency at which the AS5048B is read is set using: poll_AS5048B_Interval | |
The frequency at which the RPM is displayed as a ROS info statement is set using: infoInterval |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
# 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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
#!/usr/bin/env python | |
# check_yaw_from_odom.py | |
# Running Turtlebot in simulation yaw ranges from 3.14 to -3.14 | |
# which converts in degrees to 180 degrees and -180 degrees respectively | |
import rospy | |
from nav_msgs.msg import Odometry | |
from tf.transformations import euler_from_quaternion, quaternion_from_euler | |
print("starting check_yaw_from_odom") | |
def get_rotation (msg): |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
/* | |
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 |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
# 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 |
OlderNewer