|
From: <wg_...@us...> - 2009-09-02 03:50:41
|
Revision: 23669
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=23669&view=rev
Author: wg_cmeyers
Date: 2009-09-02 03:50:32 +0000 (Wed, 02 Sep 2009)
Log Message:
-----------
Deleted old files
Added Paths:
-----------
pkg/trunk/sandbox/texas/texas.yaml
Removed Paths:
-------------
pkg/trunk/sandbox/texas/dallas.yaml
pkg/trunk/sandbox/texas/dallas_base_controller.yaml
pkg/trunk/sandbox/texas/drive_base.launch
pkg/trunk/sandbox/texas/drive_base_joy.launch
pkg/trunk/sandbox/texas/msg/TexasCmd.msg
pkg/trunk/sandbox/texas/tdrive.py
pkg/trunk/sandbox/texas/teleop_texas_keyboard.cpp
Deleted: pkg/trunk/sandbox/texas/dallas.yaml
===================================================================
--- pkg/trunk/sandbox/texas/dallas.yaml 2009-09-02 03:47:56 UTC (rev 23668)
+++ pkg/trunk/sandbox/texas/dallas.yaml 2009-09-02 03:50:32 UTC (rev 23669)
@@ -1,13 +0,0 @@
-dallas_controller:
- type: DallasController
- kp_caster_steer: 10.0
- joints:
- caster: bl_caster_rotation_joint
- wheel_l: bl_caster_l_wheel_joint
- wheel_r: bl_caster_r_wheel_joint
- caster_pid:
- p: 3
- wheel_pid:
- p: 2
-
-
Deleted: pkg/trunk/sandbox/texas/dallas_base_controller.yaml
===================================================================
--- pkg/trunk/sandbox/texas/dallas_base_controller.yaml 2009-09-02 03:47:56 UTC (rev 23668)
+++ pkg/trunk/sandbox/texas/dallas_base_controller.yaml 2009-09-02 03:50:32 UTC (rev 23669)
@@ -1,46 +0,0 @@
-caster_names: bl_caster_rotation_link
-
-type: Pr2BaseController
-
-caster_pid_gains: &caster_pid_gains
- p: 3.0
- d: 0.0
- i: 0.1
- i_clamp: 4.0
-wheel_pid_gains: &wheel_pid_gains
- p: 2.0
- d: 0.0
- i: 0.01
- i_clamp: 0.4
-
-bl_caster_l_wheel_joint:
- *wheel_pid_gains
-bl_caster_r_wheel_joint:
- *wheel_pid_gains
-
-bl_caster_rotation_joint:
- *caster_pid_gains
-
-caster_speed_threshold: 0.2
-caster_position_error_threshold: 0.05
-wheel_speed_threshold: 0.2
-caster_effort_threshold: 3.45
-wheel_effort_threshold: 3.45
-kp_wheel_steer: 2.0
-alpha_stall: 0.5
-kp_caster_steer: 40.0
-timeout: 0.4
-max_accel:
- ax: 1.0
- ay: 2.0
- alphaz: 2.0
-
-state_publish_time: 0.25
-
-max_vel:
- vx: 1.0
- vy: 1.0
- omegaz: 2.0
-
-cmd_topic:
- /cmd_vel
Deleted: pkg/trunk/sandbox/texas/drive_base.launch
===================================================================
--- pkg/trunk/sandbox/texas/drive_base.launch 2009-09-02 03:47:56 UTC (rev 23668)
+++ pkg/trunk/sandbox/texas/drive_base.launch 2009-09-02 03:50:32 UTC (rev 23669)
@@ -1,14 +0,0 @@
-<launch>
-
- <rosparam command="load" file="$(find texas)/dallas_base_controller.yaml" ns="pr2_base_controller"/>
- <node pkg="pr2_mechanism_control" type="spawner.py" args="pr2_base_controller" />
-
- <!-- Swapping walk and run. Run (Caps) is now super slow -->
- <param name="walk_vel" value="0.4" />
- <param name="run_vel" value="0.1" />
- <param name="yaw_rate" value="0.5" />
- <param name="yaw_run_rate" value="0.2" />
- <node pkg="teleop_pr2" type="teleop_pr2_keyboard" output="screen">
- </node>
-
-</launch>
Deleted: pkg/trunk/sandbox/texas/drive_base_joy.launch
===================================================================
--- pkg/trunk/sandbox/texas/drive_base_joy.launch 2009-09-02 03:47:56 UTC (rev 23668)
+++ pkg/trunk/sandbox/texas/drive_base_joy.launch 2009-09-02 03:50:32 UTC (rev 23669)
@@ -1,40 +0,0 @@
-<launch>
-
- <rosparam command="load" file="$(find texas)/dallas_base_controller.yaml" ns="pr2_base_controller"/>
- <node pkg="pr2_mechanism_control" type="spawner.py" args="pr2_base_controller" />
-
- <group name="joystick_teleop">
- <!-- Axes -->
- <param name="axis_vx" value="3" type="int"/>
- <param name="axis_vy" value="-1" type="int"/>
- <param name="axis_vw" value="2" type="int"/>
- <param name="axis_pan" value="0" type="int"/>
- <param name="axis_tilt" value="3" type="int"/>
-
- <!-- Base velocities -->
- <param name="max_vw" value="1.0" />
- <param name="max_vx" value="0.5" />
- <param name="max_vy" value="0.5" />
- <param name="max_vw_run" value="2.0" />
- <param name="max_vx_run" value="2.0" />
- <param name="max_vy_run" value="2.0" />
-
- <!-- Head -->
- <param name="max_pan" value="2.7" />
- <param name="max_tilt" value="1.4" />
- <param name="min_tilt" value="-0.4" />
- <param name="tilt_step" value="0.015" />
- <param name="pan_step" value="0.02" />
-
- <!-- Button maps for logitech -->
- <param name="run_button" value="5" type="int" />
- <param name="torso_dn_button" value="1" type="int" />
- <param name="torso_up_button" value="3" type="int" />
- <param name="head_button" value="6" type="int" />
- <param name="deadman_button" value="4" type="int"/>
-
- <node pkg="teleop_pr2" type="teleop_pr2" output="screen"/>
- </group>
-
-
-</launch>
Deleted: pkg/trunk/sandbox/texas/msg/TexasCmd.msg
===================================================================
--- pkg/trunk/sandbox/texas/msg/TexasCmd.msg 2009-09-02 03:47:56 UTC (rev 23668)
+++ pkg/trunk/sandbox/texas/msg/TexasCmd.msg 2009-09-02 03:50:32 UTC (rev 23669)
@@ -1,2 +0,0 @@
-float64 angle
-float64 velocity
\ No newline at end of file
Deleted: pkg/trunk/sandbox/texas/tdrive.py
===================================================================
--- pkg/trunk/sandbox/texas/tdrive.py 2009-09-02 03:47:56 UTC (rev 23668)
+++ pkg/trunk/sandbox/texas/tdrive.py 2009-09-02 03:50:32 UTC (rev 23669)
@@ -1,102 +0,0 @@
-#! /usr/bin/env python
-# Copyright (c) 2008, Willow Garage, Inc.
-# 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
-# notice, this list of conditions and the following disclaimer.
-# * Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in the
-# documentation and/or other materials provided with the distribution.
-# * Neither the name of the Willow Garage, Inc. nor the names of its
-# contributors may be used to endorse or promote products derived from
-# this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
-# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
-# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
-# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
-# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
-# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
-# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
-# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
-# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
-# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-
-# Author: Dallas Goecker
-
-import time
-import random
-import roslib
-roslib.load_manifest('texas')
-import rospy
-from std_msgs.msg import Float64
-from mechanism_msgs.msg import JointStates
-from texas.msg import TexasCmd
-
-STRAIGHT = 0.82
-ROTATION_JOINT = 'bl_caster_rotation_joint'
-SPEED = 6.0
-PI = 3.14159
-
-class LastMessage():
- def __init__(self, topic, msg_type):
- self.msg = None
- rospy.Subscriber(topic, msg_type, self.callback)
-
- def last(self):
- return self.msg
-
- def callback(self, msg):
- self._last_time = rospy.get_time()
- self.msg = msg
-
- def get_timeout(self):
- return rospy.get_time() - self._last_time
-
-def main():
- angle = STRAIGHT
- speed = -SPEED
- last_time = 0
- rospy.init_node('tdrive', anonymous=True)
- last_state = LastMessage('/joint_states', JointStates)
- tx_cmd = LastMessage('texas_cmd', TexasCmd)
-
- pub_steer = rospy.Publisher("/caster_bl/caster/set_command", Float64)
- pub_drive = rospy.Publisher("/caster/drive_velocity", Float64)
- pub_steer.publish(Float64(0.0))
- pub_drive.publish(Float64(0.0))
- print "tdrive.py: Waiting for robot JointStates publication..."
- while not last_state.msg and not rospy.is_shutdown(): pass
- print "tdrive.py: Waiting for TexasCmd publication..."
- while not tx_cmd.msg and not rospy.is_shutdown(): pass
- print "tdrive.py: looping..."
- while not rospy.is_shutdown():
- time.sleep(0.10)
-
- # Get angle, velocity from command
- drive_cmd = tx_cmd.last()
- drive_vel = drive_cmd.velocity
- drive_angle = drive_cmd.angle
- # Safety timeout
- if tx_cmd.get_timeout() > 3:
- drive_vel = 0.0
-
- joint_state = last_state.last()
- rotation_state = None
- for state in joint_state.joints:
- if state.name == ROTATION_JOINT:
- rotation_state = state
- break
- if not rotation_state:
- print "The %s joint was not found in the mechanism state" % ROTATION_JOINT
-
- # Steers the caster to be straight
- pub_steer.publish(Float64(6.0 * (drive_angle - rotation_state.position)))
- pub_drive.publish(Float64(drive_vel))
-
-if __name__ == '__main__':
- main()
Deleted: pkg/trunk/sandbox/texas/teleop_texas_keyboard.cpp
===================================================================
--- pkg/trunk/sandbox/texas/teleop_texas_keyboard.cpp 2009-09-02 03:47:56 UTC (rev 23668)
+++ pkg/trunk/sandbox/texas/teleop_texas_keyboard.cpp 2009-09-02 03:50:32 UTC (rev 23669)
@@ -1,196 +0,0 @@
-/*
- * teleop_texas
- * Copyright (c) 2008, Willow Garage, Inc.
- * 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
- * notice, this list of conditions and the following disclaimer.
- * * Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in the
- * documentation and/or other materials provided with the distribution.
- * * Neither the name of the <ORGANIZATION> nor the names of its
- * contributors may be used to endorse or promote products derived from
- * this software without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
- * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
- * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
- * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
- * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
- * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
- * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
- * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
- * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
- * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- */
-
-// Author: Kevin Watts
-
-/**
-
-@mainpage
-
-@b teleop_texas_keyboard Teleops a DallasBot from a keyboard
-
-<hr>
-
-@section usage Usage
-@verbatim
-$ teleop_texas_keyboard [standard ROS args]
-@endverbatim
-
-Key mappings are printed to screen on startup.
-
-<hr>
-
-@section topic ROS topics
-
-Subscribes to (name / type):
-- None
-
-Publishes to (name / type):
-- @b "texas/TexasCmd" : Command
-
-<hr>
-
-@section parameters ROS parameters
-
-- None
-
- **/
-
-#include <termios.h>
-#include <signal.h>
-#include <math.h>
-#include <stdlib.h>
-
-#include <ros/ros.h>
-
-#include <texas/TexasCmd.h>
-
-#define CMD_TOPIC "texas_cmd"
-
-#define KEYCODE_A 0x61
-#define KEYCODE_D 0x64
-#define KEYCODE_S 0x73
-#define KEYCODE_W 0x77
-
-class TeleopTexasKeyboard
-{
- private:
- double angle_, velocity_;
- double max_vel_;
-
- ros::NodeHandle n_;
- ros::Publisher texas_pub_;
-
- public:
- void init()
- {
- angle_ = 0.0;
- velocity_ = 0.0;
-
- texas_pub_ = n_.advertise<texas::TexasCmd>(CMD_TOPIC, 1);
-
- // Max velocity of caster
- n_.param("~max_vel", max_vel_, 6.0);
- }
-
- ~TeleopTexasKeyboard() { }
- void keyboardLoop();
-
-};
-
-int kfd = 0;
-struct termios cooked, raw;
-
-void quit(int sig)
-{
- tcsetattr(kfd, TCSANOW, &cooked);
- exit(0);
-}
-
-int main(int argc, char** argv)
-{
- ros::init(argc, argv, "head_keyboard");
-
- TeleopTexasKeyboard thk;
- thk.init();
-
- signal(SIGINT,quit);
-
- thk.keyboardLoop();
-
- return(0);
-}
-
-void TeleopTexasKeyboard::keyboardLoop()
-{
- char c;
- bool dirty=false;
-
- // get the console in raw mode
- tcgetattr(kfd, &cooked);
- memcpy(&raw, &cooked, sizeof(struct termios));
- raw.c_lflag &=~ (ICANON | ECHO);
- // Setting a new line, then end of file
- raw.c_cc[VEOL] = 1;
- raw.c_cc[VEOF] = 2;
- tcsetattr(kfd, TCSANOW, &raw);
-
- puts("Reading from keyboard");
- puts("---------------------------");
- puts("Use 'WASD' to move");
-
- for(;;)
- {
- // get the next event from the keyboard
- if(read(kfd, &c, 1) < 0)
- {
- perror("read():");
- exit(-1);
- }
-
- switch(c)
- {
- case KEYCODE_W:
- velocity_ += 1.0;
- dirty = true;
- break;
- case KEYCODE_S:
- velocity_ -= 1.0;
- dirty = true;
- break;
- case KEYCODE_A:
- angle_ += 0.5;
- dirty = true;
- break;
- case KEYCODE_D:
- angle_ -= 0.5;
- dirty = true;
- break;
- default:
- velocity_ = 0.0;
- dirty = true;
- break;
- }
-
- // Bound velocity
- velocity_ = std::max(std::min(velocity_, max_vel_), - max_vel_);
-
- if (dirty == true)
- {
- texas::TexasCmd cmd;
- cmd.angle = angle_;
- cmd.velocity = velocity_;
-
- texas_pub_.publish(cmd);
- }
-
-
- }
-}
Copied: pkg/trunk/sandbox/texas/texas.yaml (from rev 23667, pkg/trunk/sandbox/texas/dallas_base_controller.yaml)
===================================================================
--- pkg/trunk/sandbox/texas/texas.yaml (rev 0)
+++ pkg/trunk/sandbox/texas/texas.yaml 2009-09-02 03:50:32 UTC (rev 23669)
@@ -0,0 +1,46 @@
+caster_names: bl_caster_rotation_link
+
+type: Pr2BaseController
+
+caster_pid_gains: &caster_pid_gains
+ p: 3.0
+ d: 0.0
+ i: 0.1
+ i_clamp: 4.0
+wheel_pid_gains: &wheel_pid_gains
+ p: 2.0
+ d: 0.0
+ i: 0.01
+ i_clamp: 0.4
+
+bl_caster_l_wheel_joint:
+ *wheel_pid_gains
+bl_caster_r_wheel_joint:
+ *wheel_pid_gains
+
+bl_caster_rotation_joint:
+ *caster_pid_gains
+
+caster_speed_threshold: 0.2
+caster_position_error_threshold: 0.05
+wheel_speed_threshold: 0.2
+caster_effort_threshold: 3.45
+wheel_effort_threshold: 3.45
+kp_wheel_steer: 2.0
+alpha_stall: 0.5
+kp_caster_steer: 40.0
+timeout: 0.4
+max_accel:
+ ax: 1.0
+ ay: 2.0
+ alphaz: 2.0
+
+state_publish_time: 0.25
+
+max_vel:
+ vx: 1.0
+ vy: 1.0
+ omegaz: 2.0
+
+cmd_topic:
+ /cmd_vel
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|