Skip to content
Snippets Groups Projects
Commit d3393434 authored by Irene Garcia Camacho's avatar Irene Garcia Camacho
Browse files

Changed name from "move base module" to "move platform module"

parent 9841724e
No related branches found
No related tags found
No related merge requests found
......@@ -93,7 +93,7 @@ generate_dynamic_reconfigure_options(
cfg/NavModule.cfg
cfg/TTSModule.cfg
cfg/ArmModule.cfg
cfg/MoveBaseModule.cfg
cfg/MovePlatformModule.cfg
)
###################################
......@@ -107,7 +107,7 @@ generate_dynamic_reconfigure_options(
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
LIBRARIES gripper_module play_motion_module head_module torso_module nav_module tts_module arm_module move_base_module
LIBRARIES gripper_module play_motion_module head_module torso_module nav_module tts_module arm_module move_platform_module
CATKIN_DEPENDS roscpp dynamic_reconfigure iri_ros_tools actionlib play_motion_msgs control_msgs geometry_msgs std_srvs move_base_msgs tf nav_msgs pal_navigation_msgs pal_waypoint_msgs pal_interaction_msgs
# DEPENDS system_lib
......@@ -230,19 +230,19 @@ target_link_libraries(arm_module ${iriutils_LIBRARY})
add_dependencies(arm_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ library
add_library(move_base_module
src/move_base_module.cpp
add_library(move_platform_module
src/move_platform_module.cpp
)
target_link_libraries(move_base_module ${catkin_LIBRARIES})
target_link_libraries(move_base_module ${iriutils_LIBRARY})
target_link_libraries(move_platform_module ${catkin_LIBRARIES})
target_link_libraries(move_platform_module ${iriutils_LIBRARY})
##Link to other modules
##target_link_libraries(new_module <module path>/lib<module_name>.so)
## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
add_dependencies(move_base_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
add_dependencies(move_platform_module ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
......
......@@ -31,7 +31,7 @@
# Author:
PACKAGE='move_base_module'
PACKAGE='move_platform_module'
from dynamic_reconfigure.parameter_generator_catkin import *
......@@ -39,10 +39,10 @@ gen = ParameterGenerator()
# Name Type Reconfiguration level Description Default Min Max
#gen.add("velocity_scale_factor", double_t, 0, "Maximum velocity scale factor", 0.5, 0.0, 1.0)
gen.add("rate_hz", double_t, 0, "Move base module rate in Hz", 1.0, 1.0, 100.0)
gen.add("rate_hz", double_t, 0, "Move platform module rate in Hz", 1.0, 1.0, 100.0)
gen.add("cmd_vel_rate_hz", double_t, 0, "Cmd vel publish rate in Hz", 10.0, 1.0, 100.0)
gen.add("distance_tol", double_t, 0, "Tolerancec for the distance", 0.05, 0.001, 0.5)
gen.add("velocity", double_t, 0, "Velocity", 0.2, 0.1, 0.8)
exit(gen.generate(PACKAGE, "MoveBaseModuleAlgorithm", "MoveBaseModule"))
exit(gen.generate(PACKAGE, "MovePlatformModuleAlgorithm", "MovePlatformModule"))
#ifndef _MOVE_BASE_MODULE_H
#define _MOVE_BASE_MODULE_H
#ifndef _MOVE_PLATFORM_MODULE_H
#define _MOVE_PLATFORM_MODULE_H
#include <iri_ros_tools/module.h>
#include <iri_ros_tools/module_action.h>
#include <tiago_modules/MoveBaseModuleConfig.h>
#include <tiago_modules/MovePlatformModuleConfig.h>
//Action
#include <moveit_msgs/MoveGroupAction.h>
......@@ -20,19 +20,19 @@
#include <geometry_msgs/Pose.h>
//States
typedef enum {MOVE_BASE_MODULE_IDLE, MOVE_BASE_MODULE_START, MOVE_BASE_MODULE_WAIT} move_base_module_state_t;
typedef enum {MOVE_PLATFORM_MODULE_IDLE, MOVE_PLATFORM_MODULE_START, MOVE_PLATFORM_MODULE_WAIT} move_platform_module_state_t;
//Status
typedef enum {MOVE_BASE_MODULE_RUNNING,
MOVE_BASE_MODULE_SUCCESS,
MOVE_BASE_MODULE_STOPPED} move_base_module_status_t;
typedef enum {MOVE_PLATFORM_MODULE_RUNNING,
MOVE_PLATFORM_MODULE_SUCCESS,
MOVE_PLATFORM_MODULE_STOPPED} move_platform_module_status_t;
class CMoveBaseModule : public CModule<move_base_module::MoveBaseModuleConfig>
class CMovePlatformModule : public CModule<move_platform_module::MovePlatformModuleConfig>
{
private:
move_base_module::MoveBaseModuleConfig config;
move_platform_module::MovePlatformModuleConfig config;
// odometry
CROSWatchdog joint_states_watchdog;
......@@ -42,8 +42,8 @@ class CMoveBaseModule : public CModule<move_base_module::MoveBaseModuleConfig>
void odom_callback(const nav_msgs::Odometry::ConstPtr& msg);
//Variables
move_base_module_state_t state;
move_base_module_status_t status;
move_platform_module_state_t state;
move_platform_module_status_t status;
bool new_position;
bool cancel_pending;
......@@ -59,19 +59,19 @@ class CMoveBaseModule : public CModule<move_base_module::MoveBaseModuleConfig>
protected:
void state_machine(void);
void reconfigure_callback(move_base_module::MoveBaseModuleConfig &config, uint32_t level);
void reconfigure_callback(move_platform_module::MovePlatformModuleConfig &config, uint32_t level);
void cmd_vel_pub(const ros::TimerEvent& event);
public:
CMoveBaseModule(const std::string &name,const std::string &name_space=std::string(""));
CMovePlatformModule(const std::string &name,const std::string &name_space=std::string(""));
// general functions
void move_base(double distance);
void move_platform(double distance);
void get_current_pose(geometry_msgs::PoseStamped &pose);
void stop(void);
bool is_finished(void);
move_base_module_status_t get_status(void);
move_platform_module_status_t get_status(void);
~CMoveBaseModule();
~CMovePlatformModule();
};
#endif
#include <tiago_modules/move_base_module.h>
#include <tiago_modules/move_platform_module.h>
CMoveBaseModule::CMoveBaseModule(const std::string &name,const std::string &name_space) : CModule(name,name_space)
CMovePlatformModule::CMovePlatformModule(const std::string &name,const std::string &name_space) : CModule(name,name_space)
{
this->start_operation();
// initialize odometry subscriber
this->odom_subscriber = this->module_nh.subscribe("/mobile_base_controller/odom",1,&CMoveBaseModule::odom_callback,this);
this->odom_subscriber = this->module_nh.subscribe("/mobile_base_controller/odom",1,&CMovePlatformModule::odom_callback,this);
//Variables
this->state=MOVE_BASE_MODULE_IDLE;
this->status=MOVE_BASE_MODULE_SUCCESS;
this->state=MOVE_PLATFORM_MODULE_IDLE;
this->status=MOVE_PLATFORM_MODULE_SUCCESS;
this->new_position=false;
this->cancel_pending=false;
this->target_achieved=false;
......@@ -23,57 +23,57 @@ CMoveBaseModule::CMoveBaseModule(const std::string &name,const std::string &name
this->cmd_vel_goal.angular.x=0.0;
this->cmd_vel_goal.angular.y=0.0;
this->cmd_vel_goal.angular.z=0.0;
this->cmd_vel_timer=this->module_nh.createTimer(ros::Duration(1.0/this->config.cmd_vel_rate_hz),&CMoveBaseModule::cmd_vel_pub,this);
this->cmd_vel_timer=this->module_nh.createTimer(ros::Duration(1.0/this->config.cmd_vel_rate_hz),&CMovePlatformModule::cmd_vel_pub,this);
this->cmd_vel_timer.stop();
}
/* State machine */
void CMoveBaseModule::state_machine(void)
void CMovePlatformModule::state_machine(void)
{
switch(this->state)
{
case MOVE_BASE_MODULE_IDLE: ROS_DEBUG("CMoveBaseModule: Idle");
case MOVE_PLATFORM_MODULE_IDLE: ROS_DEBUG("CMovePlatformModule: Idle");
if(this->new_position)
{
this->new_position=false;
this->state=MOVE_BASE_MODULE_START;
this->state=MOVE_PLATFORM_MODULE_START;
}
else
this->state=MOVE_BASE_MODULE_IDLE;
this->state=MOVE_PLATFORM_MODULE_IDLE;
break;
case MOVE_BASE_MODULE_START: ROS_DEBUG("CMoveBaseModule: Start");
case MOVE_PLATFORM_MODULE_START: ROS_DEBUG("CMovePlatformModule: Start");
this->cmd_vel_timer.start();
this->state=MOVE_BASE_MODULE_WAIT;
this->state=MOVE_PLATFORM_MODULE_WAIT;
break;
case MOVE_BASE_MODULE_WAIT: ROS_DEBUG("CMoveBaseModule: Move base");
case MOVE_PLATFORM_MODULE_WAIT: ROS_DEBUG("CMovePlatformModule: Move platform");
if(this->target_achieved)
{
this->cmd_vel_timer.stop();
this->target_achieved=false;
this->state=MOVE_BASE_MODULE_IDLE;
this->status=MOVE_BASE_MODULE_SUCCESS;
this->state=MOVE_PLATFORM_MODULE_IDLE;
this->status=MOVE_PLATFORM_MODULE_SUCCESS;
}
else if(this->cancel_pending)
{
this->cmd_vel_timer.stop();
this->cancel_pending=false;
this->state=MOVE_BASE_MODULE_IDLE;
this->status=MOVE_BASE_MODULE_STOPPED;
this->state=MOVE_PLATFORM_MODULE_IDLE;
this->status=MOVE_PLATFORM_MODULE_STOPPED;
}
else
{
this->state=MOVE_BASE_MODULE_WAIT;
this->state=MOVE_PLATFORM_MODULE_WAIT;
}
break;
}
}
void CMoveBaseModule::reconfigure_callback(move_base_module::MoveBaseModuleConfig &config, uint32_t level)
void CMovePlatformModule::reconfigure_callback(move_platform_module::MovePlatformModuleConfig &config, uint32_t level)
{
ROS_DEBUG("CMoveBaseModule : reconfigure callback");
ROS_DEBUG("CMovePlatformModule : reconfigure callback");
this->lock();
this->config=config;
/* set the module rate */
......@@ -85,9 +85,9 @@ void CMoveBaseModule::reconfigure_callback(move_base_module::MoveBaseModuleConfi
this->unlock();
}
void CMoveBaseModule::odom_callback(const nav_msgs::Odometry::ConstPtr& msg)
void CMovePlatformModule::odom_callback(const nav_msgs::Odometry::ConstPtr& msg)
{
ROS_DEBUG("CMoveBaseModule: Odometry callback");
ROS_DEBUG("CMovePlatformModule: Odometry callback");
double init_odom_rot;
double difference;
......@@ -96,7 +96,7 @@ void CMoveBaseModule::odom_callback(const nav_msgs::Odometry::ConstPtr& msg)
{
this->target_odom.pose.pose.position.x = msg->pose.pose.position.x + this->target;
}
else if(this->state!=MOVE_BASE_MODULE_IDLE)
else if(this->state!=MOVE_PLATFORM_MODULE_IDLE)
{
difference = std::abs(this->target_odom.pose.pose.position.x - msg->pose.pose.position.x);
if(difference < this->distance_tol)
......@@ -107,14 +107,14 @@ void CMoveBaseModule::odom_callback(const nav_msgs::Odometry::ConstPtr& msg)
this->unlock();
}
void CMoveBaseModule::cmd_vel_pub(const ros::TimerEvent& event)
void CMovePlatformModule::cmd_vel_pub(const ros::TimerEvent& event)
{
ROS_DEBUG("CMoveBaseModule: Cmd_vel pusblish");
ROS_DEBUG("CMovePlatformModule: Cmd_vel pusblish");
this->cmd_vel_publisher.publish(this->cmd_vel_goal);
}
// pose motion
void CMoveBaseModule::move_base(double distance)
void CMovePlatformModule::move_platform(double distance)
{
this->lock();
if(!this->is_finished())
......@@ -128,25 +128,25 @@ void CMoveBaseModule::move_base(double distance)
this->unlock();
}
void CMoveBaseModule::stop(void)
void CMovePlatformModule::stop(void)
{
if(this->state!=MOVE_BASE_MODULE_IDLE)
if(this->state!=MOVE_PLATFORM_MODULE_IDLE)
this->cancel_pending=true;
}
bool CMoveBaseModule::is_finished(void)
bool CMovePlatformModule::is_finished(void)
{
if(this->state==MOVE_BASE_MODULE_IDLE && this->new_position==false)
if(this->state==MOVE_PLATFORM_MODULE_IDLE && this->new_position==false)
return true;
else
return false;
}
move_base_module_status_t CMoveBaseModule::get_status(void)
move_platform_module_status_t CMovePlatformModule::get_status(void)
{
return this->status;
}
CMoveBaseModule::~CMoveBaseModule()
CMovePlatformModule::~CMovePlatformModule()
{
}
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