Skip to content
Snippets Groups Projects
Commit 5ea32d94 authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Fix from driver_base to iri_base_driver. Other structure changes

parent 70fb702a
No related branches found
No related tags found
No related merge requests found
cmake_minimum_required(VERSION 2.8.3) cmake_minimum_required(VERSION 2.8.3)
project(iri_segway_rmp200) project(iri_segway_rmp200_driver)
## Find catkin macros and libraries ## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz) ## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
......
...@@ -33,7 +33,7 @@ ...@@ -33,7 +33,7 @@
PACKAGE='iri_segway_rmp200' PACKAGE='iri_segway_rmp200'
from driver_base.msg import SensorLevels from iri_base_driver.msg import SensorLevels
from dynamic_reconfigure.parameter_generator_catkin import * from dynamic_reconfigure.parameter_generator_catkin import *
gen = ParameterGenerator() gen = ParameterGenerator()
......
Background\ ColorR=0.0941176
Background\ ColorG=0
Background\ ColorB=0.466667
Fixed\ Frame=/base_link
Target\ Frame=/base_link
Grid.Alpha=0.5
Grid.Cell\ Size=1
Grid.ColorR=0.898039
Grid.ColorG=0.898039
Grid.ColorB=0.898039
Grid.Enabled=1
Grid.Line\ Style=0
Grid.Line\ Width=0.03
Grid.Normal\ Cell\ Count=0
Grid.OffsetX=10
Grid.OffsetY=10
Grid.OffsetZ=0
Grid.Plane=0
Grid.Plane\ Cell\ Count=23
Grid.Reference\ Frame=<Fixed Frame>
Robot\ Model.Alpha=0.8
Robot\ Model.Collision\ Enabled=0
Robot\ Model.Enabled=1
Robot\ Model.Robot\ Description=tibi/robot_description
Robot\ Model.TF\ Prefix=
Robot\ Model.Update\ Interval=0
Robot\ Model.Visual\ Enabled=1
Robot\:\ Robot\ Model\ Link\ base_linkShow\ Axes=0
Robot\:\ Robot\ Model\ Link\ base_linkShow\ Trail=0
TF.All\ Enabled=1
TF.Enabled=1
TF.Frame\ Timeout=15
TF.Marker\ Scale=1
TF.Show\ Arrows=0
TF.Show\ Axes=1
TF.Show\ Names=1
TF.Update\ Interval=0
Tool\ 2D\ Nav\ GoalTopic=goal
Tool\ 2D\ Pose\ EstimateTopic=initialpose
Camera\ Type=rviz::OrbitViewController
Camera\ Config=1.06657 3.62862 5.24714 -0.0820465 -0.535663 0.273504
Property\ Grid\ State=selection=;expanded=.Global Options,TF.Enabled,TF.Enabled.TF.StatusTopStatus,TF.Enabled.TF.Tree;scrollpos=0,0;splitterpos=227,455;ispageselected=1
[Display0]
Name=Grid
Package=rviz
ClassName=rviz::GridDisplay
[Display1]
Name=Robot Model
Package=rviz
ClassName=rviz::RobotModelDisplay
[Display2]
Name=TF
Package=rviz
ClassName=rviz::TFDisplay
Background\ ColorB=1
Background\ ColorG=0
Background\ ColorR=0
Camera\ Config=0.726 0.702812 10.1652 -4.08803 -3.83136 -4.95288
Camera\ Type=rviz::OrbitViewController
Fixed\ Frame=/base_link
Grid.Alpha=0.5
Grid.Cell\ Size=1
Grid.ColorB=0
Grid.ColorG=0
Grid.ColorR=0
Grid.Enabled=1
Grid.Line\ Style=0
Grid.Line\ Width=0.03
Grid.Normal\ Cell\ Count=0
Grid.OffsetX=0
Grid.OffsetY=0
Grid.OffsetZ=0
Grid.Plane=0
Grid.Plane\ Cell\ Count=43
Grid.Reference\ Frame=<Fixed Frame>
Property\ Grid\ Splitter=500,78
Property\ Grid\ State=expanded=.Global Options,.Global Status,Tibi.Enabled,Tibi.Status;splitterratio=0.5
QMainWindow=000000ff00000000fd00000003000000000000011d0000028bfc0200000001fb000000100044006900730070006c00610079007301000000190000028b000000c300ffffff00000001000001310000028bfc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000019000000a70000005100fffffffb0000000a0056006900650077007301000000c600000131000000a100fffffffb0000001200530065006c0065006300740069006f006e01000001fd000000a70000005100ffffff00000003000005150000003efc0100000001fb0000000800540069006d00650100000000000005150000021400ffffff000002bb0000028b00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Robot\:\ Tibi\ Link\ base_linkAlpha=1
Robot\:\ Tibi\ Link\ base_linkEnabled=1
Robot\:\ Tibi\ Link\ base_linkShow\ Axes=0
Robot\:\ Tibi\ Link\ base_linkShow\ Trail=0
Target\ Frame=<Fixed Frame>
Tibi.Alpha=1
Tibi.Collision\ Enabled=0
Tibi.Enabled=1
Tibi.Robot\ Description=robot_description
Tibi.TF\ Prefix=
Tibi.Update\ Interval=0
Tibi.Visual\ Enabled=1
Tool\ 2D\ Nav\ GoalTopic=/goal
Tool\ 2D\ Pose\ EstimateTopic=initialpose
[Display0]
ClassName=rviz::GridDisplay
Name=Grid
[Display1]
ClassName=rviz::RobotModelDisplay
Name=Tibi
[Window]
Height=780
Width=1317
X=-8
Y=-28
velocity_scale_factor: 1.0
acceleration_scale_factor: 0.25
turn_rate_scale_factor: 1.0
current_limit_scale_factor: 1.0
gain_schedule: 2
cmd_vel_watchdog: 2.0
\ No newline at end of file
<!-- %Tag(FULL)%-->
<launch>
<!-- iri segway node -->
<node respawn="true"
pkg="iri_segway_rmp200"
type="iri_segway_rmp200"
name="iri_segway_rmp200"
launch-prefix="xterm -e ddd --args">
<param name="dev" type="string" value="/dev/input/js0" />
<param name="deadzone" value="0.12" />
</node>
</launch>
<!-- %EndTag(FULL)%-->
<!-- -->
<launch>
<!-- iri segway node -->
<!-- published topics: /segway/status -->
<!-- subscribed topics: /segway/cmd_vel -->
<!-- service clients: -->
<!-- service servers: -->
<!-- action clients: -->
<!-- action servers: -->
<node pkg ="iri_segway_rmp200"
type="iri_segway_rmp200"
name="segway"
output="screen"/>
<!-- segway urdf model -->
<param name="robot_description" command="cat $(find iri_segway_rmp200)/model/iri_segway_rmp200.urdf" />
<!-- robot state publisher node -->
<node pkg ="robot_state_publisher"
type="state_publisher"
name="robot_state_publisher">
</node>
</launch>
<!-- -->
<launch>
<!-- iri segway node -->
<!-- published topics: /segway/status -->
<!-- subscribed topics: /segway/cmd_vel -->
<!-- service clients: -->
<!-- service servers: -->
<!-- action clients: -->
<!-- action servers: -->
<include file="$(find iri_segway_rmp200)/launch/iri_segway_rmp200.launch">
</include>
<node name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find iri_segway_rmp200)/config/iri_segway_rmp200_rviz.vcg" />
</launch>
<?xml version="1.0"?>
<!-- -->
<launch>
<arg name="name" default="robot" />
<arg name="config_path" default="$(find iri_segway_rmp200_driver)/config" />
<arg name="config_file" default="params.yaml" />
<arg name="output" default="log" />
<arg name="launch_prefix" default="" />
<group ns="$(arg name)">
<node pkg ="iri_segway_rmp200_driver"
type="iri_segway_rmp200_driver"
name="segway_driver"
output="$(arg output)"
launch-prefix="$(arg launch_prefix)">
<rosparam file="$(arg config_path)/$(arg config_file)" command="load" />
</node>
</group>
</launch>
\ No newline at end of file
<!-- -->
<launch>
<include file="$(find tibi_dabo_base)/machines/$(env ROBOT)_$(env ROS_MODE).machines" />
<group ns="$(env ROBOT)">
<!-- segway rmp 200 -->
<!-- published topics: /$(env ROBOT)/segway/status -->
<!-- subscribed topics: /$(env ROBOT)/segway/cmd_vel -->
<!-- service clients: -->
<!-- service servers: -->
<!-- action clients: -->
<!-- action servers: -->
<node pkg ="iri_segway_rmp200"
type="iri_segway_rmp200"
name="segway"
output="screen"
machine="nav">
<param name="velocity_scale_factor" value="1.0"/>
<param name="acceleration_scale_factor" value="0.25"/>
<param name="turn_rate_scale_factor" value="1.0"/>
<param name="current_limit_scale_factor" value="1.0"/>
<param name="gain_schedule" value="2"/>
<param name="cmd_vel_watchdog" value="2.0"/>
</node>
</group>
</launch>
...@@ -14,5 +14,4 @@ ...@@ -14,5 +14,4 @@
</visual> </visual>
</link> </link>
</robot> </robot>
\ No newline at end of file
<?xml version="1.0"?> <?xml version="1.0"?>
<package> <package>
<name>iri_segway_rmp200</name> <name>iri_segway_rmp200_driver</name>
<version>1.0.0</version> <version>1.0.0</version>
<description>Segway RMP200 driver ROS wrapper</description> <description>Segway RMP200 driver ROS wrapper</description>
......
...@@ -99,7 +99,7 @@ void SegwayRmp200Driver::config_update(Config& new_cfg, uint32_t level) ...@@ -99,7 +99,7 @@ void SegwayRmp200Driver::config_update(Config& new_cfg, uint32_t level)
try try
{ {
if(this->getState() > SegwayRmp200Driver::CLOSED) if(this->getState() > iri_base_driver::CLOSED)
{ {
segway_->set_velocity_scale_factor(new_cfg.velocity_scale_factor); segway_->set_velocity_scale_factor(new_cfg.velocity_scale_factor);
segway_->set_acceleration_scale_factor(new_cfg.acceleration_scale_factor); segway_->set_acceleration_scale_factor(new_cfg.acceleration_scale_factor);
......
...@@ -8,7 +8,8 @@ SegwayRmp200DriverNode::SegwayRmp200DriverNode(ros::NodeHandle &nh) try : ...@@ -8,7 +8,8 @@ SegwayRmp200DriverNode::SegwayRmp200DriverNode(ros::NodeHandle &nh) try :
event_server_ = CEventServer::instance(); event_server_ = CEventServer::instance();
//init class attributes if necessary //init class attributes if necessary
this->loop_rate_ = 50;//in [Hz] double loop_rate = 50;//in [Hz]
this->setRate(loop_rate);
// [init publishers] // [init publishers]
this->status_publisher_ = this->public_node_handle_.advertise<iri_segway_rmp_msgs::SegwayRMP200Status>("status", 100); this->status_publisher_ = this->public_node_handle_.advertise<iri_segway_rmp_msgs::SegwayRMP200Status>("status", 100);
...@@ -43,7 +44,7 @@ void SegwayRmp200DriverNode::mainNodeThread(void) ...@@ -43,7 +44,7 @@ void SegwayRmp200DriverNode::mainNodeThread(void)
{ {
case SegwayRmp200Driver::NO_USB: case SegwayRmp200Driver::NO_USB:
ROS_WARN("SegwayRmp200DriverNode: The USB cable has been disconnected"); ROS_WARN("SegwayRmp200DriverNode: The USB cable has been disconnected");
driver_.goClosed(); driver_.goState(iri_base_driver::CLOSED);
break; break;
case SegwayRmp200Driver::POWER_OFF: case SegwayRmp200Driver::POWER_OFF:
...@@ -284,6 +285,6 @@ void SegwayRmp200DriverNode::update_cmd_vel_watchdog(void) ...@@ -284,6 +285,6 @@ void SegwayRmp200DriverNode::update_cmd_vel_watchdog(void)
/* main function */ /* main function */
int main(int argc,char *argv[]) int main(int argc,char *argv[])
{ {
return driver_base::main<SegwayRmp200DriverNode>(argc,argv,"segway_rmp200_driver_node"); return iri_base_driver::main<SegwayRmp200DriverNode>(argc,argv,"segway_rmp200_driver_node");
} }
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment