Skip to content

Commit

Permalink
Fixed int to double power load and clean up
Browse files Browse the repository at this point in the history
  • Loading branch information
pooyanjamshidi committed Mar 15, 2018
1 parent 1a3bf0d commit 2c46688
Show file tree
Hide file tree
Showing 4 changed files with 32 additions and 36 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ include_directories(
# Declare a C++ library
add_library(config_manager SHARED src/config_plugin.cpp)
add_dependencies(config_manager ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(config_manager ${roscpp_LIBRARIES} ${GAZEBO_LIBRARIES} ${JSONCPP_LIBRARIES})
target_link_libraries(config_manager ${roscpp_LIBRARIES} ${GAZEBO_LIBRARIES} ${Boost_LIBRARIES} ${JSONCPP_LIBRARIES})

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
Expand Down
2 changes: 1 addition & 1 deletion src/config_list.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"0":{
"config_id": 100,
"power_load": 50,
"power_load": 50.7,
"speed": 0.5
},
"1":{
Expand Down
16 changes: 6 additions & 10 deletions src/config_plugin.cpp
Original file line number Diff line number Diff line change
@@ -1,19 +1,11 @@
#include <gazebo/common/Plugin.hh>
#include "gazebo/common/CommonTypes.hh"
#include "gazebo/physics/physics.hh"
#include <ros/ros.h>
#include <ros/subscribe_options.h>
#include "ROS_debugging.h"
#include "std_msgs/String.h"
#include "jsoncpp/json/json.h"
#include "brass_gazebo_battery/SetLoad.h"
#include "brass_gazebo_config_manager/SetConfig.h"
#include <boost/thread/mutex.hpp>


#include <fstream>
#include <iostream>
#define CONFIGURATION_DEBUG

namespace gazebo{
class GAZEBO_VISIBLE ConfigurationPlugin : public ModelPlugin
Expand All @@ -30,6 +22,7 @@ protected: Json::Value config_list;

public: ConfigurationPlugin()
{
ROS_GREEN_STREAM("Creating the configuration manager plugin");
this->power_load = 0;
this->default_config = 0;
this->current_config = this->default_config;
Expand Down Expand Up @@ -68,6 +61,8 @@ protected: Json::Value config_list;
Json::Reader json_reader;
std::string config_path = _sdf->Get<std::string>("config_list_path");
this->default_config = _sdf->Get<int>("default_config");
this->current_config = this->default_config;

std::ifstream config_file(config_path, std::ifstream::binary);
json_reader.parse(config_file, this->config_list, false);

Expand All @@ -76,8 +71,9 @@ protected: Json::Value config_list;
public: virtual void Init()
{
std::string load = config_list[std::to_string(this->default_config)]["power_load"].asString();
this->power_load = std::stoi(load.c_str());
this->power_load = std::stod(load.c_str());
SetPowerLoad(this->power_load);
ROS_GREEN_STREAM("Default configuration has been set");
}

public: bool SetPowerLoad(double power_load)
Expand All @@ -104,7 +100,7 @@ public: bool SetConfiguration(brass_gazebo_config_manager::SetConfig::Request &r
this->current_config = req.current_config;
ROS_GREEN_STREAM("New configuration of the robot: " << this->current_config);
std::string load = config_list[std::to_string(this->current_config)]["power_load"].asString();
this->power_load = std::stoi(load.c_str());
this->power_load = std::stod(load.c_str());
SetPowerLoad(this->power_load);
lock.unlock();
res.result = true;
Expand Down
48 changes: 24 additions & 24 deletions test/worlds/p2-cp1-1.world
Original file line number Diff line number Diff line change
Expand Up @@ -2263,73 +2263,73 @@
</link>


<plugin filename="libbattery_discharge.so" name="battery">
<!--<plugin filename="libbattery_discharge.so" name="battery">-->


<ros_node>cp1_ros_node</ros_node>
<!--<ros_node>cp1_node</ros_node>-->


<link_name>body</link_name>
<!--<link_name>body</link_name>-->


<battery_name>brass_battery</battery_name>
<!--<battery_name>brass_battery</battery_name>-->


<constant_coef>12.694</constant_coef>
<!--<constant_coef>12.694</constant_coef>-->


<linear_coef>-3.1424</linear_coef>
<!--<linear_coef>-3.1424</linear_coef>-->


<initial_charge>1.1665</initial_charge>
<!--<initial_charge>1.1665</initial_charge>-->


<capacity>1.2009</capacity>
<!--<capacity>1.2009</capacity>-->


<resistance>0.061523</resistance>
<!--<resistance>0.061523</resistance>-->


<smooth_current_tau>1.9499</smooth_current_tau>
<!--<smooth_current_tau>1.9499</smooth_current_tau>-->


<charge_rate>2</charge_rate>
<!--<charge_rate>2</charge_rate>-->


<!-- If you charge your battery at a 10-amp rate and you need to replace 36 amp-hours in the battery.
To determine how long (in hours) you will need to charge your battery, divided 36 by 10 = 3.6 or 3.6 hours to recharge your battery. -->
<!--&lt;!&ndash; If you charge your battery at a 10-amp rate and you need to replace 36 amp-hours in the battery.-->
<!--To determine how long (in hours) you will need to charge your battery, divided 36 by 10 = 3.6 or 3.6 hours to recharge your battery. &ndash;&gt;-->


</plugin>
<!--</plugin>-->


<plugin filename="libbattery_consumer.so" name="consumer">
<!--<plugin filename="libbattery_consumer.so" name="consumer">-->


<ros_node>cp1_ros_node</ros_node>
<!--<ros_node>cp1_node</ros_node>-->


<link_name>body</link_name>
<!--<link_name>body</link_name>-->


<battery_name>brass_battery</battery_name>
<!--<battery_name>brass_battery</battery_name>-->


<power_load>6.6</power_load>
<!--<power_load>6.6</power_load>-->

<!--power load = 6.6 W -->
<!--&lt;!&ndash;power load = 6.6 W &ndash;&gt;-->


</plugin>
<!--</plugin>-->

<plugin filename="libconfig_manager.so" name="configuration_manager">

<config_list_path>src/config_list.json</config_list_path>
<config_list_path>/cp1/config/config_list.json</config_list_path>
<default_config>0</default_config>
<ros_node>cp1_ros_node</ros_node>
<ros_node>cp1_node</ros_node>

</plugin>


</model>

Expand Down

0 comments on commit 2c46688

Please sign in to comment.